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 <array>
18#include <limits>
19#include <string>
20
21#include "geometry_msgs/msg/pose.hpp"
22#include "semantic_components/semantic_component_interface.hpp"
23
24namespace semantic_components
25{
26
27class PoseSensor : public SemanticComponentInterface<geometry_msgs::msg::Pose>
28{
29public:
31 explicit PoseSensor(const std::string & name)
33 name, {{name + '/' + "position.x"},
34 {name + '/' + "position.y"},
35 {name + '/' + "position.z"},
36 {name + '/' + "orientation.x"},
37 {name + '/' + "orientation.y"},
38 {name + '/' + "orientation.z"},
39 {name + '/' + "orientation.w"}})
40 {
41 }
43
48 std::array<double, 3> get_position() const
49 {
50 std::array<double, 3> position;
51 for (auto i = 0u; i < position.size(); ++i)
52 {
53 position[i] = state_interfaces_[i].get().get_value();
54 }
55 return position;
56 }
57
59
64 std::array<double, 4> get_orientation() const
65 {
66 std::array<double, 4> orientation;
67 const std::size_t interface_offset{3};
68 for (auto i = 0u; i < orientation.size(); ++i)
69 {
70 orientation[i] = state_interfaces_[interface_offset + i].get().get_value();
71 }
72 return orientation;
73 }
74
76
79 bool get_values_as_message(geometry_msgs::msg::Pose & message) const
80 {
81 const auto [position_x, position_y, position_z] = get_position();
82 const auto [orientation_x, orientation_y, orientation_z, orientation_w] = get_orientation();
83
84 message.position.x = position_x;
85 message.position.y = position_y;
86 message.position.z = position_z;
87 message.orientation.x = orientation_x;
88 message.orientation.y = orientation_y;
89 message.orientation.z = orientation_z;
90 message.orientation.w = orientation_w;
91
92 return true;
93 }
94};
95
96} // namespace semantic_components
97
98#endif // SEMANTIC_COMPONENTS__POSE_SENSOR_HPP_
Definition pose_sensor.hpp:28
std::array< double, 4 > get_orientation() const
Update and return orientation.
Definition pose_sensor.hpp:64
PoseSensor(const std::string &name)
Constructor for a standard pose sensor with interface names set based on sensor name.
Definition pose_sensor.hpp:31
std::array< double, 3 > get_position() const
Update and return position.
Definition pose_sensor.hpp:48
bool get_values_as_message(geometry_msgs::msg::Pose &message) const
Fill pose message with current values.
Definition pose_sensor.hpp:79
Definition semantic_component_interface.hpp:28