$search
00001 /* 00002 * torso_control.h 00003 * 00004 * Created on: Jun 30, 2010 00005 * Author: christian 00006 */ 00007 00008 #ifndef TORSO_CONTROL_H_ 00009 #define TORSO_CONTROL_H_ 00010 #include <ros/ros.h> 00011 #include <pr2_controllers_msgs/SingleJointPositionAction.h> 00012 #include <actionlib/client/simple_action_client.h> 00013 00014 00015 00016 00017 namespace simple_robot_control{ 00018 00019 class Torso 00020 { 00021 private: 00022 actionlib::SimpleActionClient<pr2_controllers_msgs::SingleJointPositionAction> torso_client_; 00023 00024 public: 00025 //Action client initialization 00026 Torso(); 00027 ~Torso(); 00028 00029 //tell the torso to go to the specified position between 0.0 and 0.3. 00030 bool move(double position, bool wait = true); 00031 00032 }; 00033 00034 } 00035 00036 #endif /* TORSO_CONTROL_H_ */