Go to the documentation of this file.
18 #ifndef __ROSEE_EE_HAL__
19 #define __ROSEE_EE_HAL__
23 #include <sensor_msgs/JointState.h>
28 #include <unordered_map>
31 #include <Eigen/Dense>
32 #include <yaml-cpp/yaml.h>
38 #include <rosee_msg/HandInfo.h>
39 #include <rosee_msg/MotorPhalangePressure.h>
42 #define HAL_CREATE_OBJECT(className) \
43 extern "C" ::ROSEE::EEHal* create_object_##className ( ros::NodeHandle* nh) { \
44 return new className(nh); \
58 typedef std::shared_ptr<EEHal>
Ptr;
64 virtual bool sense() = 0;
66 virtual bool move() = 0;
87 virtual bool getTipsJacobiansNormal(std::unordered_map<std::string, Eigen::MatrixXd>& tips_jacobian_normal) {
return false;}
88 virtual bool getTipsJacobiansFriction(std::unordered_map<std::string, Eigen::MatrixXd>& tips_jacobian_friction) {
return false;}
160 rosee_msg::HandInfo::Request& request,
161 rosee_msg::HandInfo::Response& response);
168 #endif // __ROSEE_EE_HAL__
EEHal(ros::NodeHandle *nh)
bool initPressureSensing()
ros::ServiceServer _hand_info_server
ros::Publisher _joint_state_pub
virtual bool setHandInfoCallback()
Here service is advertise and callback set: if derived class wants to use different callback,...
bool handInfoEEHalCallback(rosee_msg::HandInfo::Request &request, rosee_msg::HandInfo::Response &response)
void motor_reference_clbk(const sensor_msgs::JointState::ConstPtr &msg)
virtual bool isHandInfoPresent()
virtual bool getTipsForcesNormal(Eigen::VectorXd &tips_forces_normal)
rosee_msg::HandInfo::Response _hand_info_response
virtual bool getTipJointToTipFrameX(Eigen::VectorXd &tip_joint_to_tip_frame_x)
Eigen::VectorXd tip_joint_to_tip_frame_x
sensor_msgs::JointState _js_msg
virtual bool getTransmissionAugmentedMatrices(std::unordered_map< std::string, Eigen::MatrixXd > &transmission_augmented_matrices)
Eigen::MatrixXd getPressure() const
Class representing an end-effector.
std::vector< std::string > motors_names
virtual bool getMotorStiffness(Eigen::VectorXd &motors_stiffness)
Eigen::VectorXd motors_stiffness
virtual bool init_hand_info_response()
init the service message with info parsed from yaml file, ie info that will not change according to h...
virtual bool parseHandInfo()
Eigen::VectorXd getMotorReference() const
std::shared_ptr< EEHal > Ptr
virtual bool getTipsJacobiansFriction(std::unordered_map< std::string, Eigen::MatrixXd > &tips_jacobian_friction)
virtual bool getTipsFrictions(Eigen::VectorXd &tips_friction)
Eigen::VectorXd tips_frictions
virtual bool getTipsJacobiansNormal(std::unordered_map< std::string, Eigen::MatrixXd > &tips_jacobian_normal)
virtual bool getMotorsNames(std::vector< std::string > &motors_names)
sensor_msgs::JointState _mr_msg
Eigen::VectorXd getJointPosition() const
std::string _hand_info_service_name
virtual bool checkCommandPub()
virtual bool getMotorTorqueLimits(Eigen::VectorXd &motors_torque_limits)
std::vector< std::string > fingers_names
virtual bool getFingersNames(std::vector< std::string > &fingers_names)
ros::Subscriber _motor_reference_sub
Eigen::VectorXd getJointEffort() const
virtual bool getTipJointToTipFrameY(Eigen::VectorXd &tip_joint_to_tip_frame_y)
Eigen::VectorXd motors_torque_limits
virtual bool getTransmissionSquareMatrices(std::unordered_map< std::string, Eigen::MatrixXd > &transmission_square_matrices)
Eigen::VectorXd tip_joint_to_tip_frame_y
virtual bool publish_joint_state()
rosee_msg::MotorPhalangePressure _pressure_msg
virtual bool getTipsForcesFriction(Eigen::VectorXd &tips_forces_friction)
ros::Publisher _pressure_pub
virtual bool getTransmissionMatrix(Eigen::MatrixXd &transmission_matrix)
std::shared_ptr< const EEHal > ConstPtr
end-effector
Author(s): Luca Muratore
, Davide Torielli , Liana Bertoni
autogenerated on Sat Dec 14 2024 03:49:26