point_head.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 
00003 #include <actionlib/client/simple_action_client.h>
00004 #include <pr2_controllers_msgs/PointHeadAction.h>
00005 
00006 // Our Action interface type, provided as a typedef for convenience
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     //Initialize the client for the Action interface to the head controller
00019     point_head_client_ = new PointHeadClient("/pan_tilt_trajectory_controller/point_head_action", true);
00020 
00021     //wait for head controller action server to come up
00022     while(!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     //the goal message we will be sending
00036     pr2_controllers_msgs::PointHeadGoal goal;
00037 
00038     //the target point, expressed in the requested frame
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     //we are pointing the high-def camera frame
00045     //(pointing_axis defaults to X-axis)
00046     goal.pointing_frame = "kinect2_depth_frame";
00047     goal.pointing_axis.x = 1;
00048     goal.pointing_axis.y = 0;
00049     goal.pointing_axis.z = 0;
00050 
00051     //take at least 0.5 seconds to get there
00052     goal.min_duration = ros::Duration(0.5);
00053 
00054     //and go no faster than 1 rad/s
00055     goal.max_velocity = 1.0;
00056 
00057     //send the goal
00058     point_head_client_->sendGoal(goal);
00059 
00060     //wait for it to get there (abort after 2 secs to prevent getting stuck)
00061     point_head_client_->waitForResult(ros::Duration(2));
00062   }
00063 
00065   void shakeHead(int n)
00066   {
00067     int count = 0;
00068     while (ros::ok() && ++count <= n )
00069     {
00070       //Looks at a point forward (x=5m), slightly left (y=1m), and 1.2m up
00071       lookAt("base_link", 2.0, 1.0, 1.2);
00072 
00073       //Looks at a point forward (x=5m), slightly right (y=-1m), and 1.2m up
00074       lookAt("base_link", 2.0, -1.0, 1.2);
00075     }
00076   }
00077 };
00078 
00079 int main(int argc, char** argv)
00080 {
00081   //init the ROS node
00082   ros::init(argc, argv, "robot_driver");
00083 
00084   RobotHead head;
00085   head.shakeHead(3);
00086   // head.lookAt("map", 2.4908,-1.5124,0);
00087 }


robotican_demos
Author(s):
autogenerated on Fri Oct 27 2017 03:02:45