Loading [MathJax]/extensions/tex2jax.js
ros2_control - rolling
All Classes Namespaces Functions Variables Typedefs Enumerations Pages
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
semantic_components::ForceTorqueSensor Class Reference
Inheritance diagram for semantic_components::ForceTorqueSensor:
Inheritance graph
[legend]
Collaboration diagram for semantic_components::ForceTorqueSensor:
Collaboration graph
[legend]

Public Member Functions

 ForceTorqueSensor (const std::string &name)
 Constructor for "standard" 6D FTS.
 
 ForceTorqueSensor (const std::string &interface_force_x, const std::string &interface_force_y, const std::string &interface_force_z, const std::string &interface_torque_x, const std::string &interface_torque_y, const std::string &interface_torque_z)
 Constructor for 6D FTS with custom interface names.
 
std::array< double, 3 > get_forces () const
 Return forces.
 
std::array< double, 3 > get_torques () const
 Return torque.
 
bool get_values_as_message (geometry_msgs::msg::Wrench &message) const
 Return Wrench message with forces and torques.
 
- Public Member Functions inherited from semantic_components::SemanticComponentInterface< geometry_msgs::msg::Wrench >
 SemanticComponentInterface (const std::string &name, const std::vector< std::string > &interface_names)
 
 SemanticComponentInterface (const std::string &name, std::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::Wrench &)
 Return values as MessageReturnType.
 

Protected Member Functions

void update_data_from_interfaces () const
 Update the data from the state interfaces.
 

Protected Attributes

std::array< double, 6 > data_
 Array to store the data of the FT sensors.
 
std::array< bool, 6 > existing_axes_
 Vector with existing axes for sensors with less then 6D axes.
 
- Protected Attributes inherited from semantic_components::SemanticComponentInterface< geometry_msgs::msg::Wrench >
std::string name_
 
std::vector< std::string > interface_names_
 
std::vector< std::reference_wrapper< hardware_interface::LoanedStateInterface > > state_interfaces_
 

Constructor & Destructor Documentation

◆ ForceTorqueSensor()

semantic_components::ForceTorqueSensor::ForceTorqueSensor ( const std::string &  interface_force_x,
const std::string &  interface_force_y,
const std::string &  interface_force_z,
const std::string &  interface_torque_x,
const std::string &  interface_torque_y,
const std::string &  interface_torque_z 
)
inline

Constructor for 6D FTS with custom interface names.

Constructor for 6D FTS with custom interface names or FTS with less then six measurement axes, e.g., 1D and 2D force load cells. For non existing axes interface is empty string, i.e., ("");

The name should be in the following order: force X, force Y, force Z, torque X, torque Y, torque Z.

Member Function Documentation

◆ get_forces()

std::array< double, 3 > semantic_components::ForceTorqueSensor::get_forces ( ) const
inline

Return forces.

Return forces of a FTS.

Returns
array of size 3 with force values (x, y, z).

◆ get_torques()

std::array< double, 3 > semantic_components::ForceTorqueSensor::get_torques ( ) const
inline

Return torque.

Return torques of a FTS.

Returns
array of size 3 with torque values (x, y, z).

◆ get_values_as_message()

bool semantic_components::ForceTorqueSensor::get_values_as_message ( geometry_msgs::msg::Wrench &  message) const
inline

Return Wrench message with forces and torques.

Constructs and return a wrench message from the current values. The method assumes that the interface names on the construction are in the following order: force X, force Y, force Z, torque X, torque Y, torque Z.

Returns
wrench message from values;

◆ update_data_from_interfaces()

void semantic_components::ForceTorqueSensor::update_data_from_interfaces ( ) const
inlineprotected

Update the data from the state interfaces.

Note
The method is thread-safe and non-blocking.
This method might return stale data if the data is not updated. This is to ensure that the data from the sensor is not discontinuous.

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