Go to the documentation of this file.00001
00028 #ifndef SHADOWHAND_SUBSCRIBER_H_
00029 #define SHADOWHAND_SUBSCRIBER_H_
00030
00031 #include <ros/ros.h>
00032 #include <vector>
00033 #include <string>
00034 #include <map>
00035
00036 #include <boost/smart_ptr.hpp>
00037
00038
00039 #include <sr_robot_msgs/joints_data.h>
00040 #include <sr_robot_msgs/joint.h>
00041 #include <sr_robot_msgs/contrlr.h>
00042 #include <sr_robot_msgs/sendupdate.h>
00043 #include <sr_robot_msgs/config.h>
00044 #include <sr_robot_msgs/reverseKinematics.h>
00045 #include <std_msgs/Float64.h>
00046
00047 #include "sr_hand/hand/sr_articulated_robot.h"
00048
00049 using namespace ros;
00050 using namespace shadowrobot;
00051
00052 namespace shadowrobot
00053 {
00054
00059 class SRSubscriber
00060 {
00061 public:
00067 SRSubscriber( boost::shared_ptr<SRArticulatedRobot> sr_art_robot );
00068
00070 ~SRSubscriber();
00071
00072 private:
00074 NodeHandle node, n_tilde;
00075
00077 boost::shared_ptr<SRArticulatedRobot> sr_articulated_robot;
00078
00080 void init();
00081
00083
00085
00092 void sendupdateCallback( const sr_robot_msgs::sendupdateConstPtr& msg );
00094 Subscriber sendupdate_sub;
00095
00102 void cmd_callback(const std_msgs::Float64ConstPtr& msg, std::string& joint_name);
00104 std::vector<Subscriber> controllers_sub;
00105
00111 void contrlrCallback( const sr_robot_msgs::contrlrConstPtr& msg );
00113 Subscriber contrlr_sub;
00114
00119 void configCallback( const sr_robot_msgs::configConstPtr& msg );
00121 Subscriber config_sub;
00122 };
00123
00124 }
00125
00126 #endif