14#ifndef SEMANTIC_COMPONENTS__POSE_SENSOR_HPP_
15#define SEMANTIC_COMPONENTS__POSE_SENSOR_HPP_
21#include "geometry_msgs/msg/pose.hpp"
22#include "semantic_components/semantic_component_interface.hpp"
24namespace semantic_components
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"}})
50 std::array<double, 3> position;
51 for (
auto i = 0u; i < position.size(); ++i)
53 position[i] = state_interfaces_[i].get().get_value();
66 std::array<double, 4> orientation;
67 const std::size_t interface_offset{3};
68 for (
auto i = 0u; i < orientation.size(); ++i)
70 orientation[i] = state_interfaces_[interface_offset + i].get().get_value();
81 const auto [position_x, position_y, position_z] =
get_position();
82 const auto [orientation_x, orientation_y, orientation_z, orientation_w] =
get_orientation();
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;
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