Class representing an end-effector.
More...
#include <EEHal.h>
Class representing an end-effector.
Definition at line 54 of file EEHal.h.
◆ ConstPtr
◆ Ptr
◆ EEHal()
◆ ~EEHal()
virtual ROSEE::EEHal::~EEHal |
( |
| ) |
|
|
inlinevirtual |
◆ checkCommandPub()
bool ROSEE::EEHal::checkCommandPub |
( |
| ) |
|
|
virtual |
◆ getFingersNames()
bool ROSEE::EEHal::getFingersNames |
( |
std::vector< std::string > & |
fingers_names | ) |
|
|
virtual |
◆ getJointEffort()
Eigen::VectorXd ROSEE::EEHal::getJointEffort |
( |
| ) |
const |
◆ getJointPosition()
Eigen::VectorXd ROSEE::EEHal::getJointPosition |
( |
| ) |
const |
◆ getMotorReference()
Eigen::VectorXd ROSEE::EEHal::getMotorReference |
( |
| ) |
const |
◆ getMotorsNames()
bool ROSEE::EEHal::getMotorsNames |
( |
std::vector< std::string > & |
motors_names | ) |
|
|
virtual |
◆ getMotorStiffness()
bool ROSEE::EEHal::getMotorStiffness |
( |
Eigen::VectorXd & |
motors_stiffness | ) |
|
|
virtual |
◆ getMotorTorqueLimits()
bool ROSEE::EEHal::getMotorTorqueLimits |
( |
Eigen::VectorXd & |
motors_torque_limits | ) |
|
|
virtual |
◆ getPressure()
Eigen::MatrixXd ROSEE::EEHal::getPressure |
( |
| ) |
const |
◆ getTipJointToTipFrameX()
bool ROSEE::EEHal::getTipJointToTipFrameX |
( |
Eigen::VectorXd & |
tip_joint_to_tip_frame_x | ) |
|
|
virtual |
◆ getTipJointToTipFrameY()
bool ROSEE::EEHal::getTipJointToTipFrameY |
( |
Eigen::VectorXd & |
tip_joint_to_tip_frame_y | ) |
|
|
virtual |
◆ getTipsForcesFriction()
virtual bool ROSEE::EEHal::getTipsForcesFriction |
( |
Eigen::VectorXd & |
tips_forces_friction | ) |
|
|
inlinevirtual |
◆ getTipsForcesNormal()
virtual bool ROSEE::EEHal::getTipsForcesNormal |
( |
Eigen::VectorXd & |
tips_forces_normal | ) |
|
|
inlinevirtual |
◆ getTipsFrictions()
bool ROSEE::EEHal::getTipsFrictions |
( |
Eigen::VectorXd & |
tips_friction | ) |
|
|
virtual |
◆ getTipsJacobiansFriction()
virtual bool ROSEE::EEHal::getTipsJacobiansFriction |
( |
std::unordered_map< std::string, Eigen::MatrixXd > & |
tips_jacobian_friction | ) |
|
|
inlinevirtual |
◆ getTipsJacobiansNormal()
virtual bool ROSEE::EEHal::getTipsJacobiansNormal |
( |
std::unordered_map< std::string, Eigen::MatrixXd > & |
tips_jacobian_normal | ) |
|
|
inlinevirtual |
◆ getTransmissionAugmentedMatrices()
virtual bool ROSEE::EEHal::getTransmissionAugmentedMatrices |
( |
std::unordered_map< std::string, Eigen::MatrixXd > & |
transmission_augmented_matrices | ) |
|
|
inlinevirtual |
◆ getTransmissionMatrix()
virtual bool ROSEE::EEHal::getTransmissionMatrix |
( |
Eigen::MatrixXd & |
transmission_matrix | ) |
|
|
inlinevirtual |
◆ getTransmissionSquareMatrices()
virtual bool ROSEE::EEHal::getTransmissionSquareMatrices |
( |
std::unordered_map< std::string, Eigen::MatrixXd > & |
transmission_square_matrices | ) |
|
|
inlinevirtual |
◆ handInfoEEHalCallback()
bool ROSEE::EEHal::handInfoEEHalCallback |
( |
rosee_msg::HandInfo::Request & |
request, |
|
|
rosee_msg::HandInfo::Response & |
response |
|
) |
| |
|
private |
◆ init_hand_info_response()
bool ROSEE::EEHal::init_hand_info_response |
( |
| ) |
|
|
virtual |
init the service message with info parsed from yaml file, ie info that will not change according to hand configuration A derived HAL can override this if necessary, since this is called by EEHalExecutor
Definition at line 217 of file EEHal.cpp.
◆ initPressureSensing()
bool ROSEE::EEHal::initPressureSensing |
( |
| ) |
|
|
protected |
◆ isHandInfoPresent()
bool ROSEE::EEHal::isHandInfoPresent |
( |
| ) |
|
|
virtual |
◆ motor_reference_clbk()
void ROSEE::EEHal::motor_reference_clbk |
( |
const sensor_msgs::JointState::ConstPtr & |
msg | ) |
|
|
private |
◆ move()
virtual bool ROSEE::EEHal::move |
( |
| ) |
|
|
pure virtual |
◆ parseHandInfo()
bool ROSEE::EEHal::parseHandInfo |
( |
| ) |
|
|
virtual |
◆ publish_joint_state()
bool ROSEE::EEHal::publish_joint_state |
( |
| ) |
|
|
virtual |
◆ publish_pressure()
bool ROSEE::EEHal::publish_pressure |
( |
| ) |
|
◆ sense()
virtual bool ROSEE::EEHal::sense |
( |
| ) |
|
|
pure virtual |
◆ setHandInfoCallback()
bool ROSEE::EEHal::setHandInfoCallback |
( |
| ) |
|
|
virtual |
Here service is advertise and callback set: if derived class wants to use different callback, they must override this and do : _hand_info_server = _nh->advertiseService(_hand_info_service_name, <custom_callback>);.
Definition at line 235 of file EEHal.cpp.
◆ _hand_info_present
bool ROSEE::EEHal::_hand_info_present |
|
private |
◆ _hand_info_response
rosee_msg::HandInfo::Response ROSEE::EEHal::_hand_info_response |
|
protected |
◆ _hand_info_server
◆ _hand_info_service_name
std::string ROSEE::EEHal::_hand_info_service_name |
|
protected |
◆ _joint_state_pub
◆ _js_msg
sensor_msgs::JointState ROSEE::EEHal::_js_msg |
|
protected |
The states that must be filled in the sense(), reading info from real/simulated robot TODO put private and create a set (no get) ?
Definition at line 136 of file EEHal.h.
◆ _motor_reference_sub
◆ _mr_msg
sensor_msgs::JointState ROSEE::EEHal::_mr_msg |
|
protected |
The references that must be read in the move() to send to the real/simulated robot TODO put private and create a get ? (no set)
Definition at line 129 of file EEHal.h.
◆ _nh
◆ _pressure_active
bool ROSEE::EEHal::_pressure_active |
◆ _pressure_msg
rosee_msg::MotorPhalangePressure ROSEE::EEHal::_pressure_msg |
|
protected |
◆ _pressure_pub
◆ fingers_names
std::vector<std::string> ROSEE::EEHal::fingers_names |
|
protected |
◆ motors_names
std::vector<std::string> ROSEE::EEHal::motors_names |
|
protected |
◆ motors_stiffness
Eigen::VectorXd ROSEE::EEHal::motors_stiffness |
|
protected |
◆ motors_torque_limits
Eigen::VectorXd ROSEE::EEHal::motors_torque_limits |
|
protected |
◆ tip_joint_to_tip_frame_x
Eigen::VectorXd ROSEE::EEHal::tip_joint_to_tip_frame_x |
|
protected |
◆ tip_joint_to_tip_frame_y
Eigen::VectorXd ROSEE::EEHal::tip_joint_to_tip_frame_y |
|
protected |
◆ tips_frictions
Eigen::VectorXd ROSEE::EEHal::tips_frictions |
|
protected |
The documentation for this class was generated from the following files: