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:
32 explicit PoseSensor(const std::string & name)
34 name, {{name + '/' + "position.x"},
35 {name + '/' + "position.y"},
36 {name + '/' + "position.z"},
37 {name + '/' + "orientation.x"},
38 {name + '/' + "orientation.y"},
39 {name + '/' + "orientation.z"},
40 {name + '/' + "orientation.w"}})
41 {
42 }
44
49 std::array<double, 3> get_position() const
50 {
51 update_data_from_interfaces();
52 std::array<double, 3> position;
53 std::copy(data_.begin(), data_.begin() + 3, position.begin());
54 return position;
55 }
56
58
63 std::array<double, 4> get_orientation() const
64 {
65 update_data_from_interfaces();
66 std::array<double, 4> orientation;
67 std::copy(data_.begin() + 3, data_.end(), orientation.begin());
68 return orientation;
69 }
70
72
75 bool get_values_as_message(geometry_msgs::msg::Pose & message) const
76 {
77 update_data_from_interfaces();
78
79 message.position.x = data_[0];
80 message.position.y = data_[1];
81 message.position.z = data_[2];
82 message.orientation.x = data_[3];
83 message.orientation.y = data_[4];
84 message.orientation.z = data_[5];
85 message.orientation.w = data_[6];
86
87 return true;
88 }
89
90private:
97 void update_data_from_interfaces() const
98 {
99 for (auto i = 0u; i < data_.size(); ++i)
100 {
101 const auto data = state_interfaces_[i].get().get_optional();
102 if (data.has_value())
103 {
104 data_[i] = data.value();
105 }
106 }
107 }
108
110 mutable std::array<double, 7> data_{{0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0}};
111};
112
113} // namespace semantic_components
114
115#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:63
PoseSensor(const std::string &name)
Constructor for a standard pose sensor with interface names set based on sensor name.
Definition pose_sensor.hpp:32
std::array< double, 3 > get_position() const
Update and return position.
Definition pose_sensor.hpp:49
bool get_values_as_message(geometry_msgs::msg::Pose &message) const
Fill pose message with current values.
Definition pose_sensor.hpp:75
Definition semantic_component_interface.hpp:28