◆ 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 |
( |
| ) |
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;
The documentation for this class was generated from the following file: