#include <wrench_manager.hpp>
Public Member Functions | |
bool | initializeWrenchComm (const std::string &end_effector, const std::string &sensor_frame, const std::string &gripping_point_frame, const std::string &sensor_topic, const std::string &calib_matrix_param) |
bool | wrenchAtGrippingPoint (const std::string &end_effector, Eigen::Matrix< double, 6, 1 > &wrench) const |
bool | wrenchAtSensorPoint (const std::string &end_effector, Eigen::Matrix< double, 6, 1 > &wrench) const |
WrenchManager (ros::NodeHandle nh_=ros::NodeHandle("~")) | |
~WrenchManager () | |
Private Member Functions | |
void | forceTorqueCB (const geometry_msgs::WrenchStamped::ConstPtr &msg) |
Private Attributes | |
std::map< std::string, Eigen::Matrix< double, 6, 6 > > | calibration_matrix_ |
std::map< std::string, ros::Subscriber > | ft_sub_ |
std::map< std::string, std::string > | gripping_frame_ |
tf::TransformListener | listener_ |
int | max_tf_attempts_ |
std::map< std::string, KDL::Wrench > | measured_wrench_ |
ros::NodeHandle | nh_ |
MatrixParser | parser_ |
std::map< std::string, ros::Publisher > | processed_ft_pub_ |
std::map< std::string, std::string > | sensor_frame_ |
std::map< std::string, KDL::Frame > | sensor_to_gripping_point_ |
Subscribes to wrench topics and produces the wrench value at a requested frame.
Definition at line 21 of file wrench_manager.hpp.
Definition at line 5 of file wrench_manager.cpp.
Definition at line 15 of file wrench_manager.cpp.
void generic_control_toolbox::WrenchManager::forceTorqueCB | ( | const geometry_msgs::WrenchStamped::ConstPtr & | msg | ) | [private] |
Obtains wrench measurements for a force torque sensor.
msg | The force torque message from the sensor node. |
Definition at line 137 of file wrench_manager.cpp.
bool generic_control_toolbox::WrenchManager::initializeWrenchComm | ( | const std::string & | end_effector, |
const std::string & | sensor_frame, | ||
const std::string & | gripping_point_frame, | ||
const std::string & | sensor_topic, | ||
const std::string & | calib_matrix_param | ||
) |
Adds a new wrench subscription. The wrench manager stores the rigid transform between the F/T sensor and the gripping point.
end_effector | The sensor arm's end-effector. |
sensor_frame | The TF frame name that represents the sensor pose. |
gripping_point_frame | The TF frame that represents the gripping point pose. |
sensor_topic | The wrench topic name for the desired sensor. |
Definition at line 17 of file wrench_manager.cpp.
bool generic_control_toolbox::WrenchManager::wrenchAtGrippingPoint | ( | const std::string & | end_effector, |
Eigen::Matrix< double, 6, 1 > & | wrench | ||
) | const |
Provides access to the measured wrench at the arm's gripping point. Wrench is expressed in the point's frame.
end_effector | The arm's end-effector name. |
wrench | The wrench at the gripping point. |
Definition at line 101 of file wrench_manager.cpp.
bool generic_control_toolbox::WrenchManager::wrenchAtSensorPoint | ( | const std::string & | end_effector, |
Eigen::Matrix< double, 6, 1 > & | wrench | ||
) | const |
Gets the original sensor measurements, at the sensor frame.
end_effector | The arm's end-effector name. |
wrench | The wrench at the sensor point. |
Definition at line 124 of file wrench_manager.cpp.
std::map<std::string, Eigen::Matrix<double, 6, 6> > generic_control_toolbox::WrenchManager::calibration_matrix_ [private] |
Definition at line 73 of file wrench_manager.hpp.
std::map<std::string, ros::Subscriber> generic_control_toolbox::WrenchManager::ft_sub_ [private] |
Definition at line 70 of file wrench_manager.hpp.
std::map<std::string, std::string> generic_control_toolbox::WrenchManager::gripping_frame_ [private] |
Definition at line 72 of file wrench_manager.hpp.
Definition at line 74 of file wrench_manager.hpp.
int generic_control_toolbox::WrenchManager::max_tf_attempts_ [private] |
Definition at line 66 of file wrench_manager.hpp.
std::map<std::string, KDL::Wrench> generic_control_toolbox::WrenchManager::measured_wrench_ [private] |
Definition at line 69 of file wrench_manager.hpp.
Definition at line 76 of file wrench_manager.hpp.
Definition at line 75 of file wrench_manager.hpp.
std::map<std::string, ros::Publisher> generic_control_toolbox::WrenchManager::processed_ft_pub_ [private] |
Definition at line 71 of file wrench_manager.hpp.
std::map<std::string, std::string> generic_control_toolbox::WrenchManager::sensor_frame_ [private] |
Definition at line 67 of file wrench_manager.hpp.
std::map<std::string, KDL::Frame> generic_control_toolbox::WrenchManager::sensor_to_gripping_point_ [private] |
Definition at line 68 of file wrench_manager.hpp.