00001 #include <ros/ros.h>
00002 
00003 #include <actionlib/client/simple_action_client.h>
00004 #include <pr2_controllers_msgs/PointHeadAction.h>
00005 
00006 
00007 typedef actionlib::SimpleActionClient<pr2_controllers_msgs::PointHeadAction> PointHeadClient;
00008 
00009 class RobotHead
00010 {
00011 private:
00012   PointHeadClient* point_head_client_;
00013 
00014 public:
00016   RobotHead()
00017   {
00018     
00019     point_head_client_ = new PointHeadClient("/head_traj_controller/point_head_action", true);
00020 
00021     
00022     while(ros::ok() && !point_head_client_->waitForServer(ros::Duration(5.0))){
00023       ROS_INFO("Waiting for the point_head_action server to come up");
00024     }
00025   }
00026 
00027   ~RobotHead()
00028   {
00029     delete point_head_client_;
00030   }
00031 
00033   void lookAt(std::string frame_id, double x, double y, double z)
00034   {
00035     
00036     pr2_controllers_msgs::PointHeadGoal goal;
00037 
00038     
00039     geometry_msgs::PointStamped point;
00040     point.header.frame_id = frame_id;
00041     point.point.x = x; point.point.y = y; point.point.z = z;
00042     goal.target = point;
00043 
00044     
00045     
00046     goal.pointing_frame = "high_def_frame";
00047 
00048     
00049     goal.min_duration = ros::Duration(0.5);
00050 
00051     
00052     goal.max_velocity = 1.0;
00053 
00054     
00055     point_head_client_->sendGoal(goal);
00056 
00057     
00058     point_head_client_->waitForResult();
00059   }
00060 
00062   void shakeHead(int n)
00063   {
00064     int count = 0;
00065     while (ros::ok() && ++count <= n )
00066     {
00067       
00068       lookAt("base_link", 5.0, 1.0, 1.2);
00069 
00070       
00071       lookAt("base_link", 5.0, -1.0, 1.2);
00072     }
00073   }
00074 };
00075 
00076 int main(int argc, char** argv)
00077 {
00078   
00079   ros::init(argc, argv, "robot_driver");
00080 
00081   RobotHead head;
00082   head.shakeHead(3);
00083 }