|
| 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 () |
| Return forces.
|
|
std::array< double, 3 > | get_torques () |
| Return torque.
|
|
bool | get_values_as_message (geometry_msgs::msg::Wrench &message) |
| Return Wrench message with forces and torques.
|
|
| 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::Wrench &) |
| Return values as MessageReturnType.
|
|
|
std::array< bool, 6 > | existing_axes_ |
| Vector with existing axes for sensors with less then 6D axes.
|
|
std::array< double, 3 > | forces_ |
|
std::array< double, 3 > | torques_ |
|
std::string | name_ |
|
std::vector< std::string > | interface_names_ |
|
std::vector< std::reference_wrapper< hardware_interface::LoanedStateInterface > > | state_interfaces_ |
|
◆ 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.
◆ get_forces()
std::array< double, 3 > semantic_components::ForceTorqueSensor::get_forces |
( |
| ) |
|
|
inline |
Return forces.
Return forces of a FTS.
- Returns
- array of size 3 with force values.
◆ get_torques()
std::array< double, 3 > semantic_components::ForceTorqueSensor::get_torques |
( |
| ) |
|
|
inline |
Return torque.
Return torques of a FTS.
- Returns
- array of size 3 with torque values.
◆ get_values_as_message()
bool semantic_components::ForceTorqueSensor::get_values_as_message |
( |
geometry_msgs::msg::Wrench & |
message | ) |
|
|
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;
The documentation for this class was generated from the following file: