ros2_control - rolling
Loading...
Searching...
No Matches
range_sensor.hpp
1// Copyright 2023 flochre
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#ifndef SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_
16#define SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_
17
18#include <string>
19#include <vector>
20
21#include "semantic_components/semantic_component_interface.hpp"
22#include "sensor_msgs/msg/range.hpp"
23
24namespace semantic_components
25{
26class RangeSensor : public SemanticComponentInterface<sensor_msgs::msg::Range>
27{
28public:
29 explicit RangeSensor(const std::string & name)
30 : SemanticComponentInterface(name, {name + "/" + "range"})
31 {
32 }
38 float get_range() const { return state_interfaces_[0].get().get_value(); }
39
41
45 bool get_values_as_message(sensor_msgs::msg::Range & message) const
46 {
47 message.range = get_range();
48 return true;
49 }
50};
51
52} // namespace semantic_components
53
54#endif // SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_
Definition range_sensor.hpp:27
bool get_values_as_message(sensor_msgs::msg::Range &message) const
Return Range message with range in meters.
Definition range_sensor.hpp:45
float get_range() const
Definition range_sensor.hpp:38
Definition semantic_component_interface.hpp:28