ROSEndEffector
ROS End-Effector package: provides a ROS-based set of standard interfaces to command robotics end-effectors in an agnostic fashion.
Public Types | Public Member Functions | Private Attributes | List of all members
ROSEE::XBot2Hal Class Reference

Concrete class which communicate directly with ROS topics. More...

#include <XBot2Hal.h>

+ Inheritance diagram for ROSEE::XBot2Hal:
+ Collaboration diagram for ROSEE::XBot2Hal:

Public Types

typedef std::shared_ptr< XBot2HalPtr
 
typedef std::shared_ptr< const XBot2HalConstPtr
 
- Public Types inherited from ROSEE::EEHal
typedef std::shared_ptr< EEHalPtr
 
typedef std::shared_ptr< const EEHalConstPtr
 

Public Member Functions

 XBot2Hal (ros::NodeHandle *nh)
 
virtual ~XBot2Hal ()
 
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 Attributes

XBot::RobotInterface::Ptr _robot
 
XBot::JointNameMap _jointPositionActualMap
 
XBot::JointNameMap _jointPositionReferenceMap
 

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
 

Detailed Description

Concrete class which communicate directly with ROS topics.

Definition at line 19 of file XBot2Hal.h.

Member Typedef Documentation

typedef std::shared_ptr<const XBot2Hal> ROSEE::XBot2Hal::ConstPtr

Definition at line 25 of file XBot2Hal.h.

typedef std::shared_ptr<XBot2Hal> ROSEE::XBot2Hal::Ptr

Definition at line 24 of file XBot2Hal.h.

Constructor & Destructor Documentation

ROSEE::XBot2Hal::XBot2Hal ( ros::NodeHandle *  nh)

Definition at line 4 of file XBot2Hal.cpp.

4  : EEHal ( nh ) {
5 
6  //little HACK to be sure xbot is ready and gazebo is unpaused (this service is on after xbot2-core
7  // is on AND gazebo is unpaused
8  ROS_INFO_STREAM("[XBot2Hal constructor]: wait for xbot2core and gazebo to be ready...");
9  ros::service::waitForService("/xbotcore/ros_ctrl/switch", -1);
10  ROS_INFO_STREAM("[XBot2Hal constructor]: xbot2core and gazebo ready!");
11 
12  //We call the xbot service to command the hand through ros
13 // std_srvs::SetBool serviceMsg;
14 // serviceMsg.request.data = true;
15 // ros::ServiceClient client = nh->serviceClient<std_srvs::SetBool>("/xbotcore/ros_ctrl/switch");
16 //
17 // if (client.call(serviceMsg) ) {
18 //
19 //
20 //
21 // if (!serviceMsg.response.success){
22 // ROS_ERROR_STREAM("[XBot2Hal constructor]: Failed to call /xbotcore/ros_ctrl/switch with error message: " << serviceMsg.response.message << ". Aborting");
23 // exit(-1);
24 // }
25 // ROS_INFO_STREAM("[XBot2Hal constructor]: Succesfully called /xbotcore/ros_ctrl/switch");
26 //
27 // } else {
28 // ROS_ERROR_STREAM("[XBot2Hal constructor]: Failed to call /xbotcore/ros_ctrl/switch. Aborting");
29 // exit(-1);
30 // }
31 
32 
33  std::string path_to_config_file = XBot::Utils::getXBotConfig();
34 
35  _robot = XBot::RobotInterface::getRobot(path_to_config_file);
36 
37  _mr_msg.name.resize(_robot->getJointNum());
38  _mr_msg.position.resize(_robot->getJointNum());
39  _js_msg.name.resize(_robot->getJointNum());
40  _js_msg.position.resize(_robot->getJointNum());
41  _js_msg.velocity.resize(_robot->getJointNum());
42  _js_msg.effort.resize(_robot->getJointNum());
43 
44 }
sensor_msgs::JointState _mr_msg
The references that must be read in the move() to send to the real/simulated robot TODO put private a...
Definition: EEHal.h:129
EEHal(ros::NodeHandle *nh)
Definition: EEHal.cpp:20
XBot::RobotInterface::Ptr _robot
Definition: XBot2Hal.h:36
sensor_msgs::JointState _js_msg
The states that must be filled in the sense(), reading info from real/simulated robot TODO put privat...
Definition: EEHal.h:136
virtual ROSEE::XBot2Hal::~XBot2Hal ( )
inlinevirtual

Definition at line 28 of file XBot2Hal.h.

28 { };

Member Function Documentation

bool ROSEE::XBot2Hal::move ( )
overridevirtual

Implements ROSEE::EEHal.

Definition at line 72 of file XBot2Hal.cpp.

72  {
73 
74  //NOTE if robot does not move, check if "rosservice call /xbotcore/ros_ctrl/switch 1"
75  for (int i=0; i<_mr_msg.position.size(); i++) {
76 
77  _jointPositionReferenceMap[_mr_msg.name.at(i)] = _mr_msg.position.at(i);
78  }
79 
80  if (! _robot->setPositionReference(_jointPositionReferenceMap)) {
81  return false;
82  }
83 
84  return _robot->move();
85 }
sensor_msgs::JointState _mr_msg
The references that must be read in the move() to send to the real/simulated robot TODO put private a...
Definition: EEHal.h:129
XBot::RobotInterface::Ptr _robot
Definition: XBot2Hal.h:36
XBot::JointNameMap _jointPositionReferenceMap
Definition: XBot2Hal.h:38
bool ROSEE::XBot2Hal::sense ( )
overridevirtual

Implements ROSEE::EEHal.

Definition at line 47 of file XBot2Hal.cpp.

47  {
48  if (! _robot->sense()){
49  return false;
50  }
51  _robot->getJointPosition(_jointPositionActualMap);
52  if (_js_msg.name.size() != _jointPositionActualMap.size() ||
53  _js_msg.position.size() != _jointPositionActualMap.size()) {
54 
55  ROS_ERROR_STREAM("[XBot2Hal::" << __func__ << "] size of _js_msg is different from the size" <<
56  " or what received from the robot (_jointPositionActualMap)");
57  return false;
58  }
59 
60  int i = 0;
61  for (auto it : _jointPositionActualMap ) {
62 
63  //TODO it is better to fill the names only once in the costructor?
64  _js_msg.name.at(i) = it.first;
65  _js_msg.position.at(i) = it.second;
66  i++;
67  }
68 
69  return true;
70 }
XBot::JointNameMap _jointPositionActualMap
Definition: XBot2Hal.h:37
XBot::RobotInterface::Ptr _robot
Definition: XBot2Hal.h:36
sensor_msgs::JointState _js_msg
The states that must be filled in the sense(), reading info from real/simulated robot TODO put privat...
Definition: EEHal.h:136

Member Data Documentation

XBot::JointNameMap ROSEE::XBot2Hal::_jointPositionActualMap
private

Definition at line 37 of file XBot2Hal.h.

XBot::JointNameMap ROSEE::XBot2Hal::_jointPositionReferenceMap
private

Definition at line 38 of file XBot2Hal.h.

XBot::RobotInterface::Ptr ROSEE::XBot2Hal::_robot
private

Definition at line 36 of file XBot2Hal.h.


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