Class PoseSensor
- Defined in File pose_sensor.hpp 
Inheritance Relationships
Base Type
- public semantic_components::SemanticComponentInterface< geometry_msgs::msg::Pose >(Template Class SemanticComponentInterface)
Class Documentation
- 
class PoseSensor : public semantic_components::SemanticComponentInterface<geometry_msgs::msg::Pose>
- Public Functions - 
inline explicit PoseSensor(const std::string &name)
- Constructor for a standard pose sensor with interface names set based on sensor name. 
 - 
virtual ~PoseSensor() = default
 - 
inline std::array<double, 3> get_position()
- Update and return position. - Update and return current pose position from state interfaces. - Returns:
- Array of position coordinates. 
 
 - 
inline std::array<double, 4> get_orientation()
- Update and return orientation. - Update and return current pose orientation from state interfaces. - Returns:
- Array of orientation coordinates in xyzw convention. 
 
 - 
inline bool get_values_as_message(geometry_msgs::msg::Pose &message)
- Fill pose message with current values. - Fill a pose message with current position and orientation from the state interfaces. 
 
- 
inline explicit PoseSensor(const std::string &name)