ROSEndEffector
ROS End-Effector package: provides a ROS-based set of standard interfaces to command robotics end-effectors in an agnostic fashion.
|
Class representing an end-effector. More...
#include <DummyHal.h>
Public Types | |
typedef std::shared_ptr< DummyHal > | Ptr |
typedef std::shared_ptr< const DummyHal > | ConstPtr |
Public Types inherited from ROSEE::EEHal | |
typedef std::shared_ptr< EEHal > | Ptr |
typedef std::shared_ptr< const EEHal > | ConstPtr |
Public Member Functions | |
DummyHal (ros::NodeHandle *nh) | |
virtual | ~DummyHal () |
virtual bool | sense () override |
virtual bool | move () override |
Public Member Functions inherited from ROSEE::EEHal | |
EEHal (ros::NodeHandle *nh) | |
virtual | ~EEHal () |
virtual bool | publish_joint_state () |
virtual bool | checkCommandPub () |
virtual bool | getFingersNames (std::vector< std::string > &fingers_names) |
virtual bool | getMotorsNames (std::vector< std::string > &motors_names) |
virtual bool | getMotorStiffness (Eigen::VectorXd &motors_stiffness) |
virtual bool | getTipsFrictions (Eigen::VectorXd &tips_friction) |
virtual bool | getMotorTorqueLimits (Eigen::VectorXd &motors_torque_limits) |
virtual bool | getTipJointToTipFrameX (Eigen::VectorXd &tip_joint_to_tip_frame_x) |
virtual bool | getTipJointToTipFrameY (Eigen::VectorXd &tip_joint_to_tip_frame_y) |
virtual bool | getTipsJacobiansNormal (std::unordered_map< std::string, Eigen::MatrixXd > &tips_jacobian_normal) |
virtual bool | getTipsJacobiansFriction (std::unordered_map< std::string, Eigen::MatrixXd > &tips_jacobian_friction) |
virtual bool | getTransmissionMatrix (Eigen::MatrixXd &transmission_matrix) |
virtual bool | getTransmissionSquareMatrices (std::unordered_map< std::string, Eigen::MatrixXd > &transmission_square_matrices) |
virtual bool | getTransmissionAugmentedMatrices (std::unordered_map< std::string, Eigen::MatrixXd > &transmission_augmented_matrices) |
virtual bool | getTipsForcesNormal (Eigen::VectorXd &tips_forces_normal) |
virtual bool | getTipsForcesFriction (Eigen::VectorXd &tips_forces_friction) |
virtual bool | parseHandInfo () |
virtual bool | isHandInfoPresent () |
virtual bool | init_hand_info_response () |
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 More... | |
virtual bool | setHandInfoCallback () |
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>);. More... | |
bool | publish_pressure () |
Eigen::VectorXd | getMotorReference () const |
Eigen::VectorXd | getJointPosition () const |
Eigen::VectorXd | getJointEffort () const |
Eigen::MatrixXd | getPressure () const |
Private Member Functions | |
void | hal_js_clbk (const sensor_msgs::JointState::ConstPtr &msg) |
Private Attributes | |
ros::Publisher | _hal_joint_state_pub |
this will publish to joint_state_publisher More... | |
ros::Subscriber | _hal_joint_state_sub |
this will subscribe to joint_state_publisher More... | |
Additional Inherited Members | |
Public Attributes inherited from ROSEE::EEHal | |
bool | _pressure_active |
Protected Member Functions inherited from ROSEE::EEHal | |
bool | initPressureSensing () |
Protected Attributes inherited from ROSEE::EEHal | |
ros::NodeHandle * | _nh |
sensor_msgs::JointState | _mr_msg |
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) More... | |
ros::Subscriber | _motor_reference_sub |
sensor_msgs::JointState | _js_msg |
The states that must be filled in the sense(), reading info from real/simulated robot TODO put private and create a set (no get) ? More... | |
ros::Publisher | _joint_state_pub |
rosee_msg::MotorPhalangePressure | _pressure_msg |
ros::Publisher | _pressure_pub |
std::vector< std::string > | fingers_names |
std::vector< std::string > | motors_names |
Eigen::VectorXd | tips_frictions |
Eigen::VectorXd | motors_torque_limits |
Eigen::VectorXd | motors_stiffness |
Eigen::VectorXd | tip_joint_to_tip_frame_x |
Eigen::VectorXd | tip_joint_to_tip_frame_y |
ros::ServiceServer | _hand_info_server |
rosee_msg::HandInfo::Response | _hand_info_response |
std::string | _hand_info_service_name |
Class representing an end-effector.
Definition at line 34 of file DummyHal.h.
typedef std::shared_ptr<const DummyHal> ROSEE::DummyHal::ConstPtr |
Definition at line 39 of file DummyHal.h.
typedef std::shared_ptr<DummyHal> ROSEE::DummyHal::Ptr |
Definition at line 38 of file DummyHal.h.
ROSEE::DummyHal::DummyHal | ( | ros::NodeHandle * | nh | ) |
Definition at line 20 of file DummyHal.cpp.
|
inlinevirtual |
Definition at line 42 of file DummyHal.h.
|
private |
Definition at line 39 of file DummyHal.cpp.
|
overridevirtual |
Implements ROSEE::EEHal.
Definition at line 34 of file DummyHal.cpp.
|
overridevirtual |
Implements ROSEE::EEHal.
Definition at line 29 of file DummyHal.cpp.
|
private |
this will publish to joint_state_publisher
Definition at line 51 of file DummyHal.h.
|
private |
this will subscribe to joint_state_publisher
Definition at line 56 of file DummyHal.h.