sr_muscle_hand_lib.hpp
Go to the documentation of this file.
00001 
00028 #ifndef _SR_MUSCLE_HAND_LIB_HPP_
00029 #define _SR_MUSCLE_HAND_LIB_HPP_
00030 
00031 #include "sr_robot_lib/sr_muscle_robot_lib.hpp"
00032 #include <std_srvs/Empty.h>
00033 
00034 // to be able to load the configuration from the
00035 // parameter server
00036 #include <ros/ros.h>
00037 #include <string>
00038 #include <vector>
00039 
00040 
00041 namespace shadow_robot
00042 {
00043 template<class StatusType, class CommandType>
00044 class SrMuscleHandLib :
00045         public SrMuscleRobotLib<StatusType, CommandType>
00046 {
00047 public:
00048   SrMuscleHandLib(hardware_interface::HardwareInterface *hw, ros::NodeHandle nh, ros::NodeHandle nhtilde,
00049                   std::string device_id, std::string joint_prefix);
00050 
00060   bool reset_muscle_driver_callback(std_srvs::Empty::Request &request,
00061                                     std_srvs::Empty::Response &response,
00062                                     int muscle_driver_index);
00063 
00064 #ifdef DEBUG_PUBLISHER
00065 
00074   bool set_debug_data_to_publish(sr_robot_msgs::SetDebugData::Request& request,
00075                                  sr_robot_msgs::SetDebugData::Response& response);
00076 #endif
00077 
00078 protected:
00086   virtual void initialize(std::vector<std::string> joint_names, std::vector<int> actuator_ids,
00087                           std::vector<shadow_joints::JointToSensor> joint_to_sensors);
00088 
00096   void initialize(std::vector<std::string> joint_names, std::vector<shadow_joints::JointToMuscle> actuator_ids,
00097                   std::vector<shadow_joints::JointToSensor> joint_to_sensors);
00098 
00099 private:
00108   std::vector<shadow_joints::JointToMuscle> read_joint_to_muscle_mapping();
00109 
00110 
00111   static const int nb_muscle_data;
00112   static const char *human_readable_muscle_data_types[];
00113   static const int32u muscle_data_types[];
00114 
00115 #ifdef DEBUG_PUBLISHER
00116 
00117   ros::ServiceServer debug_service;
00118 #endif
00119 };
00120 }  // namespace shadow_robot
00121 
00122 /* For the emacs weenies in the crowd.
00123 Local Variables:
00124    c-basic-offset: 2
00125 End:
00126 */
00127 
00128 #endif


sr_robot_lib
Author(s): Ugo Cupcic, Toni Oliver
autogenerated on Mon Jul 1 2019 20:06:26