From ff572f9d4e3d65ccb2e9191f9321c2b29de8798c Mon Sep 17 00:00:00 2001 From: Florent Chretien Date: Tue, 24 Jan 2023 15:00:03 +0100 Subject: [PATCH 1/4] add range_sensor.hpp --- .../semantic_components/range_sensor.hpp | 63 +++++++++++++++++++ 1 file changed, 63 insertions(+) create mode 100644 controller_interface/include/semantic_components/range_sensor.hpp diff --git a/controller_interface/include/semantic_components/range_sensor.hpp b/controller_interface/include/semantic_components/range_sensor.hpp new file mode 100644 index 0000000000..bbb47649a7 --- /dev/null +++ b/controller_interface/include/semantic_components/range_sensor.hpp @@ -0,0 +1,63 @@ +// Copyright 2023 +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_ +#define SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_ + +#include +#include +#include + +#include "semantic_components/semantic_component_interface.hpp" +#include "sensor_msgs/msg/range.hpp" + +namespace semantic_components +{ +class RangeSensor : public SemanticComponentInterface +{ +public: + explicit RangeSensor(const std::string & name) : SemanticComponentInterface(name, 1) + { + interface_names_.emplace_back(name_ + "/" + "range"); + } + + virtual ~RangeSensor() = default; + + /** + * Return Range reported by a sensor + * + * \return value of the range in meters + */ + float get_range() + { + return state_interfaces_[0].get().get_value();; + } + + /// Return Range message with range in meters + /** + * Constructs and return a Range message from the current values. + * \return Range message from values; + */ + bool get_values_as_message(sensor_msgs::msg::Range & message) + { + // update the message values + message.range = get_range(); + + return true; + } +}; + +} // namespace semantic_components + +#endif // SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_ From efb3305a465facb32988380ed5b715b8e95cf5f7 Mon Sep 17 00:00:00 2001 From: Florent Chretien Date: Thu, 27 Jul 2023 13:06:09 +0200 Subject: [PATCH 2/4] delete useless semicolon --- .../include/semantic_components/range_sensor.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/controller_interface/include/semantic_components/range_sensor.hpp b/controller_interface/include/semantic_components/range_sensor.hpp index bbb47649a7..d16b9c2dc9 100644 --- a/controller_interface/include/semantic_components/range_sensor.hpp +++ b/controller_interface/include/semantic_components/range_sensor.hpp @@ -41,7 +41,7 @@ class RangeSensor : public SemanticComponentInterface */ float get_range() { - return state_interfaces_[0].get().get_value();; + return state_interfaces_[0].get().get_value(); } /// Return Range message with range in meters From f0aca93a650c1568c07cdb15eb1e19659f06ceb9 Mon Sep 17 00:00:00 2001 From: Florent Date: Tue, 1 Aug 2023 19:25:41 +0600 Subject: [PATCH 3/4] run pre-commit --- .../include/semantic_components/range_sensor.hpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/controller_interface/include/semantic_components/range_sensor.hpp b/controller_interface/include/semantic_components/range_sensor.hpp index d16b9c2dc9..a51f220902 100644 --- a/controller_interface/include/semantic_components/range_sensor.hpp +++ b/controller_interface/include/semantic_components/range_sensor.hpp @@ -39,10 +39,7 @@ class RangeSensor : public SemanticComponentInterface * * \return value of the range in meters */ - float get_range() - { - return state_interfaces_[0].get().get_value(); - } + float get_range() { return state_interfaces_[0].get().get_value(); } /// Return Range message with range in meters /** From 5173a5fd125b7dc96fde3f16619373027703393c Mon Sep 17 00:00:00 2001 From: Florent Date: Fri, 4 Aug 2023 14:39:33 +0600 Subject: [PATCH 4/4] complete the copyright line --- .../include/semantic_components/range_sensor.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/controller_interface/include/semantic_components/range_sensor.hpp b/controller_interface/include/semantic_components/range_sensor.hpp index a51f220902..baa9022c75 100644 --- a/controller_interface/include/semantic_components/range_sensor.hpp +++ b/controller_interface/include/semantic_components/range_sensor.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 +// Copyright 2023 flochre // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License.