ros2_control - iron
Loading...
Searching...
No Matches
Public Member Functions | Protected Attributes | List of all members
semantic_components::PoseSensor Class Reference
Inheritance diagram for semantic_components::PoseSensor:
Inheritance graph
[legend]
Collaboration diagram for semantic_components::PoseSensor:
Collaboration graph
[legend]

Public Member Functions

 PoseSensor (const std::string &name)
 Constructor for a standard pose sensor with interface names set based on sensor name.
 
std::array< double, 3 > get_position ()
 Update and return position.
 
std::array< double, 4 > get_orientation ()
 Update and return orientation.
 
bool get_values_as_message (geometry_msgs::msg::Pose &message)
 Fill pose message with current values.
 
- Public Member Functions inherited from semantic_components::SemanticComponentInterface< geometry_msgs::msg::Pose >
 SemanticComponentInterface (const std::string &name, size_t size=0)
 
bool assign_loaned_state_interfaces (std::vector< hardware_interface::LoanedStateInterface > &state_interfaces)
 Assign loaned state interfaces from the hardware.
 
void release_interfaces ()
 Release loaned interfaces from the hardware.
 
virtual std::vector< std::string > get_state_interface_names ()
 Definition of state interface names for the component.
 
bool get_values (std::vector< double > &values) const
 Return all values.
 
bool get_values_as_message (geometry_msgs::msg::Pose &)
 Return values as MessageReturnType.
 

Protected Attributes

std::array< double, 3 > position_
 
std::array< double, 4 > orientation_
 
- Protected Attributes inherited from semantic_components::SemanticComponentInterface< geometry_msgs::msg::Pose >
std::string name_
 
std::vector< std::string > interface_names_
 
std::vector< std::reference_wrapper< hardware_interface::LoanedStateInterface > > state_interfaces_
 

Member Function Documentation

◆ get_orientation()

std::array< double, 4 > semantic_components::PoseSensor::get_orientation ( )
inline

Update and return orientation.

Update and return current pose orientation from state interfaces.

Returns
Array of orientation coordinates in xyzw convention.

◆ get_position()

std::array< double, 3 > semantic_components::PoseSensor::get_position ( )
inline

Update and return position.

Update and return current pose position from state interfaces.

Returns
Array of position coordinates.

◆ get_values_as_message()

bool semantic_components::PoseSensor::get_values_as_message ( geometry_msgs::msg::Pose &  message)
inline

Fill pose message with current values.

Fill a pose message with current position and orientation from the state interfaces.


The documentation for this class was generated from the following file: