Public Member Functions | Private Member Functions | Private Attributes
generic_control_toolbox::WrenchManager Class Reference

#include <wrench_manager.hpp>

Inheritance diagram for generic_control_toolbox::WrenchManager:
Inheritance graph
[legend]

List of all members.

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::Framesensor_to_gripping_point_

Detailed Description

Subscribes to wrench topics and produces the wrench value at a requested frame.

Definition at line 21 of file wrench_manager.hpp.


Constructor & Destructor Documentation

Definition at line 5 of file wrench_manager.cpp.

Definition at line 15 of file wrench_manager.cpp.


Member Function Documentation

void generic_control_toolbox::WrenchManager::forceTorqueCB ( const geometry_msgs::WrenchStamped::ConstPtr &  msg) [private]

Obtains wrench measurements for a force torque sensor.

Parameters:
msgThe 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.

Parameters:
end_effectorThe sensor arm's end-effector.
sensor_frameThe TF frame name that represents the sensor pose.
gripping_point_frameThe TF frame that represents the gripping point pose.
sensor_topicThe wrench topic name for the desired sensor.
Returns:
False if something goes wrong, true otherwise.

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.

Parameters:
end_effectorThe arm's end-effector name.
wrenchThe wrench at the gripping point.
Returns:
false in case of error, true otherwise.

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.

Parameters:
end_effectorThe arm's end-effector name.
wrenchThe wrench at the sensor point.
Returns:
false in case of error, true otherwise.

Definition at line 124 of file wrench_manager.cpp.


Member Data Documentation

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.

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.

Definition at line 66 of file wrench_manager.hpp.

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.

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.

Definition at line 68 of file wrench_manager.hpp.


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


generic_control_toolbox
Author(s): diogo
autogenerated on Thu Jun 6 2019 18:02:57