Public Member Functions | Private Member Functions | Private Attributes | List of all members
generic_control_toolbox::WrenchManager Class Reference

#include <wrench_manager.hpp>

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

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 setGrippingPoint (const std::string &end_effector, const std::string &gripping_point_frame)
 
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
 
bool wrenchAtSensorPointInGraspFrame (const std::string &end_effector, Eigen::Matrix< double, 6, 1 > &wrench) const
 
 WrenchManager (ros::NodeHandle nh_=ros::NodeHandle("~"))
 
 ~WrenchManager ()
 
- Public Member Functions inherited from generic_control_toolbox::ManagerBase
 ManagerBase ()
 
virtual ~ManagerBase ()
 

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::Subscriberft_sub_
 
std::map< std::string, std::string > gripping_frame_
 
tf::TransformListener listener_
 
int max_tf_attempts_
 
std::map< std::string, KDL::Wrenchmeasured_wrench_
 
ros::NodeHandle nh_
 
MatrixParser parser_
 
std::map< std::string, ros::Publisherprocessed_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

◆ WrenchManager()

generic_control_toolbox::WrenchManager::WrenchManager ( ros::NodeHandle  nh_ = ros::NodeHandle("~"))

Definition at line 5 of file wrench_manager.cpp.

◆ ~WrenchManager()

generic_control_toolbox::WrenchManager::~WrenchManager ( )

Definition at line 15 of file wrench_manager.cpp.

Member Function Documentation

◆ forceTorqueCB()

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 189 of file wrench_manager.cpp.

◆ initializeWrenchComm()

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 77 of file wrench_manager.cpp.

◆ setGrippingPoint()

bool generic_control_toolbox::WrenchManager::setGrippingPoint ( const std::string &  end_effector,
const std::string &  gripping_point_frame 
)

Set the gripping point for the given end-effector's arm.

Parameters
end_effectorThe sensor arm's end-effector.
gripping_point_frameThe TF frame that represents the gripping point pose.

Definition at line 23 of file wrench_manager.cpp.

◆ wrenchAtGrippingPoint()

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 130 of file wrench_manager.cpp.

◆ wrenchAtSensorPoint()

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 176 of file wrench_manager.cpp.

◆ wrenchAtSensorPointInGraspFrame()

bool generic_control_toolbox::WrenchManager::wrenchAtSensorPointInGraspFrame ( const std::string &  end_effector,
Eigen::Matrix< double, 6, 1 > &  wrench 
) const

Get the sensor measurements, expressed in the gripping point's 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 153 of file wrench_manager.cpp.

Member Data Documentation

◆ calibration_matrix_

std::map<std::string, Eigen::Matrix<double, 6, 6> > generic_control_toolbox::WrenchManager::calibration_matrix_
private

Definition at line 93 of file wrench_manager.hpp.

◆ ft_sub_

std::map<std::string, ros::Subscriber> generic_control_toolbox::WrenchManager::ft_sub_
private

Definition at line 90 of file wrench_manager.hpp.

◆ gripping_frame_

std::map<std::string, std::string> generic_control_toolbox::WrenchManager::gripping_frame_
private

Definition at line 92 of file wrench_manager.hpp.

◆ listener_

tf::TransformListener generic_control_toolbox::WrenchManager::listener_
private

Definition at line 94 of file wrench_manager.hpp.

◆ max_tf_attempts_

int generic_control_toolbox::WrenchManager::max_tf_attempts_
private

Definition at line 86 of file wrench_manager.hpp.

◆ measured_wrench_

std::map<std::string, KDL::Wrench> generic_control_toolbox::WrenchManager::measured_wrench_
private

Definition at line 89 of file wrench_manager.hpp.

◆ nh_

ros::NodeHandle generic_control_toolbox::WrenchManager::nh_
private

Definition at line 96 of file wrench_manager.hpp.

◆ parser_

MatrixParser generic_control_toolbox::WrenchManager::parser_
private

Definition at line 95 of file wrench_manager.hpp.

◆ processed_ft_pub_

std::map<std::string, ros::Publisher> generic_control_toolbox::WrenchManager::processed_ft_pub_
private

Definition at line 91 of file wrench_manager.hpp.

◆ sensor_frame_

std::map<std::string, std::string> generic_control_toolbox::WrenchManager::sensor_frame_
private

Definition at line 87 of file wrench_manager.hpp.

◆ sensor_to_gripping_point_

std::map<std::string, KDL::Frame> generic_control_toolbox::WrenchManager::sensor_to_gripping_point_
private

Definition at line 88 of file wrench_manager.hpp.


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


generic_control_toolbox
Author(s): diogo
autogenerated on Mon Feb 28 2022 22:24:38