Class ForceTorqueSensor

Inheritance Relationships

Base Type

Class Documentation

class ForceTorqueSensor : public semantic_components::SemanticComponentInterface<geometry_msgs::msg::Wrench>

Public Functions

inline explicit ForceTorqueSensor(const std::string &name)

Constructor for “standard” 6D FTS.

inline 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.

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.

virtual ~ForceTorqueSensor() = default
inline std::array<double, 3> get_forces()

Return forces.

Return forces of a FTS.

Returns:

array of size 3 with force values.

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

Return torque.

Return torques of a FTS.

Returns:

array of size 3 with torque values.

inline bool get_values_as_message(geometry_msgs::msg::Wrench &message)

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;

Protected Attributes

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_