ros2_control - rolling
Loading...
Searching...
No Matches
pose_sensor.hpp
1// Copyright 2024 FZI Forschungszentrum Informatik
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#ifndef SEMANTIC_COMPONENTS__POSE_SENSOR_HPP_
15#define SEMANTIC_COMPONENTS__POSE_SENSOR_HPP_
16
17#include <algorithm>
18#include <array>
19#include <limits>
20#include <string>
21
22#include "geometry_msgs/msg/pose.hpp"
23#include "semantic_components/semantic_component_interface.hpp"
24
25namespace semantic_components
26{
27
28class PoseSensor : public SemanticComponentInterface<geometry_msgs::msg::Pose>
29{
30public:
34 explicit PoseSensor(const std::string & name)
36 name, {{name + '/' + "position.x"},
37 {name + '/' + "position.y"},
38 {name + '/' + "position.z"},
39 {name + '/' + "orientation.x"},
40 {name + '/' + "orientation.y"},
41 {name + '/' + "orientation.z"},
42 {name + '/' + "orientation.w"}})
43 {
44 }
52 std::array<double, 3> get_position() const
53 {
54 update_data_from_interfaces();
55 std::array<double, 3> position;
56 std::copy(data_.begin(), data_.begin() + 3, position.begin());
57 return position;
58 }
59
67 std::array<double, 4> get_orientation() const
68 {
69 update_data_from_interfaces();
70 std::array<double, 4> orientation;
71 std::copy(data_.begin() + 3, data_.end(), orientation.begin());
72 return orientation;
73 }
74
83 bool get_values_as_message(geometry_msgs::msg::Pose & message) const
84 {
85 update_data_from_interfaces();
86
87 message.position.x = data_[0];
88 message.position.y = data_[1];
89 message.position.z = data_[2];
90 message.orientation.x = data_[3];
91 message.orientation.y = data_[4];
92 message.orientation.z = data_[5];
93 message.orientation.w = data_[6];
94
95 return true;
96 }
97
98private:
105 void update_data_from_interfaces() const
106 {
107 for (auto i = 0u; i < data_.size(); ++i)
108 {
109 const auto data = state_interfaces_[i].get().get_optional();
110 if (data.has_value())
111 {
112 data_[i] = data.value();
113 }
114 }
115 }
116
120 mutable std::array<double, 7> data_{{0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0}};
121};
122
123} // namespace semantic_components
124
125#endif // SEMANTIC_COMPONENTS__POSE_SENSOR_HPP_
Definition pose_sensor.hpp:29
std::array< double, 4 > get_orientation() const
Update and return orientation.
Definition pose_sensor.hpp:67
PoseSensor(const std::string &name)
Constructor for a standard pose sensor with interface names set based on sensor name.
Definition pose_sensor.hpp:34
std::array< double, 3 > get_position() const
Update and return position.
Definition pose_sensor.hpp:52
bool get_values_as_message(geometry_msgs::msg::Pose &message) const
Fill pose message with current values.
Definition pose_sensor.hpp:83
Definition semantic_component_interface.hpp:28