00001 00027 #ifndef _TEST_JOINT_MOVEMENT_HPP_ 00028 #define _TEST_JOINT_MOVEMENT_HPP_ 00029 00030 #include <sr_movements/movement_from_image.hpp> 00031 #include <sr_movements/movement_publisher.hpp> 00032 #include <sr_robot_msgs/JointControllerState.h> 00033 #include <std_msgs/Float64.h> 00034 #include <ros/ros.h> 00035 #include <sr_hand/hand_commander.hpp> 00036 #include <boost/smart_ptr.hpp> 00037 00038 namespace shadow_robot 00039 { 00040 class TestJointMovement 00041 { 00042 public: 00043 TestJointMovement(std::string joint_name, shadowrobot::HandCommander* hand_commander); 00044 ~TestJointMovement() {}; 00045 00046 double mse; 00047 std::map<std::string, std::vector<double> > values; 00048 00049 private: 00050 ros::Subscriber sub_; 00051 ros::Publisher pub_; 00052 00053 ros::Subscriber sr_sub_state_; 00054 ros::Subscriber sub_state_; 00055 void sr_state_cb_(const sr_robot_msgs::JointControllerState::ConstPtr& msg); 00056 void state_cb_(const control_msgs::JointControllerState::ConstPtr& msg); 00057 00058 ros::Subscriber mse_sub_; 00059 void mse_cb_(const std_msgs::Float64::ConstPtr& msg); 00060 std::string get_ROS_topic_type(std::string topic_name); 00061 00062 boost::shared_ptr<shadowrobot::MovementFromImage> mvt_from_img_; 00063 boost::shared_ptr<shadowrobot::MovementPublisher> mvt_pub_; 00064 00065 ros::NodeHandle nh_tilde_; 00066 00067 boost::shared_ptr<boost::thread> thread_; 00068 00069 std::string joint_name_; 00070 00072 boost::shared_ptr<shadowrobot::HandCommander> hand_commander_; 00073 }; 00074 } 00075 00076 /* For the emacs weenies in the crowd. 00077 Local Variables: 00078 c-basic-offset: 2 00079 End: 00080 */ 00081 00082 #endif /* _TEST_JOINT_MOVEMENT_HPP_ */