ros2_control - humble
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 <limits>
19#include <string>
20#include <vector>
21
22#include "semantic_components/semantic_component_interface.hpp"
23#include "sensor_msgs/msg/range.hpp"
24
25namespace semantic_components
26{
27class RangeSensor : public SemanticComponentInterface<sensor_msgs::msg::Range>
28{
29public:
30 explicit RangeSensor(const std::string & name) : SemanticComponentInterface(name, 1)
31 {
32 interface_names_.emplace_back(name_ + "/" + "range");
33 }
34
35 virtual ~RangeSensor() = default;
36
42 float get_range() { return state_interfaces_[0].get().get_value(); }
43
45
49 bool get_values_as_message(sensor_msgs::msg::Range & message)
50 {
51 // update the message values
52 message.range = get_range();
53
54 return true;
55 }
56};
57
58} // namespace semantic_components
59
60#endif // SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_
Definition range_sensor.hpp:28
bool get_values_as_message(sensor_msgs::msg::Range &message)
Return Range message with range in meters.
Definition range_sensor.hpp:49
float get_range()
Definition range_sensor.hpp:42
Definition semantic_component_interface.hpp:28