search_and_track_handle.cpp
Go to the documentation of this file.
00001 #include <cmath>
00002 #include <ros/ros.h>
00003 #include <tf/transform_listener.h>
00004 #include <actionlib/client/simple_action_client.h>
00005 #include <pr2_controllers_msgs/PointHeadAction.h>
00006 #include <std_srvs/Empty.h>
00007 
00008 // Our Action interface type, provided as a typedef for convenience
00009 typedef actionlib::SimpleActionClient<pr2_controllers_msgs::PointHeadAction> PointHeadClient;
00010 
00011 class RobotHead
00012 {
00013 private:
00014   PointHeadClient point_head_client_;
00015   std::string frame_to_point;
00016   tf::TransformListener listener;
00017   bool active_;
00018   ros::Time found_time_;
00019   ros::Subscriber pose_sub_;
00020   ros::ServiceServer service_on_, service_off_;
00021 
00022 public:
00024   RobotHead() : point_head_client_("/head_traj_controller/point_head_action", true),  //Initialize the client for the Action interface to the head controller
00025                 frame_to_point("/head_mount_kinect_rgb_link"),
00026                 active_(false),
00027                 found_time_(ros::Time::now())
00028   {
00029     ros::NodeHandle n; 
00030     pose_sub_ = n.subscribe("door_handle", 0, &RobotHead::track, this);
00031     service_on_ = n.advertiseService("search_and_track_handle_on", &RobotHead::switchActive, this);
00032     service_off_ = n.advertiseService("search_and_track_handle_off", &RobotHead::switchInactive, this);
00033 
00034     ros::NodeHandle nh("~");
00035     nh.param<bool>("start_active", active_, active_); //By default wait for activation by service call
00036 
00037     //wait for head controller action server to come up 
00038     while(!point_head_client_.waitForServer(ros::Duration(1.0))){
00039       ROS_INFO_THROTTLE(10, "Waiting for the point_head_action server to come up");
00040     }
00041 
00042     ROS_INFO_COND(active_, "Searching for checkerboard. Deactivate by service call");
00043     ROS_INFO_COND(!active_, "Search for checkerboard available. Activate by service call");
00044   }
00045 
00046   void track(geometry_msgs::PoseStamped ps = geometry_msgs::PoseStamped() ){
00047       found_time_ = ros::Time::now();
00048       if(active_) this->lookAt(ps);
00049   }
00050 
00051   void lookAt(geometry_msgs::PoseStamped pose_stamped)
00052   {
00053     if(!active_)return;
00054     ROS_DEBUG("Pointing head at perceived handle");
00055     //the goal message we will be sending
00056     pr2_controllers_msgs::PointHeadGoal goal;
00057     geometry_msgs::PointStamped point_stamped;
00058     point_stamped.header = pose_stamped.header;
00059     point_stamped.point = pose_stamped.pose.position;
00060     goal.target = point_stamped;
00061     goal.pointing_frame = this->frame_to_point;
00062 
00063     //take at least 0.5 seconds to get there
00064     goal.min_duration = ros::Duration(1.5);
00065 
00066     //and go no faster than 1 rad/s
00067     goal.max_velocity = 0.25;
00068 
00069     //send the goal
00070     point_head_client_.cancelAllGoals();
00071     point_head_client_.sendGoal(goal);
00072     point_head_client_.waitForResult(ros::Duration(5));
00073   }
00074 
00076   void lookAt(std::string frame_id, double x, double y, double z, double max_wait_seconds = 10.0)
00077   {
00078     if(!active_)return;
00079     //the goal message we will be sending
00080     pr2_controllers_msgs::PointHeadGoal goal;
00081 
00082     //the target point, expressed in the requested frame
00083     geometry_msgs::PointStamped point;
00084     point.header.frame_id = frame_id;
00085     point.header.stamp = ros::Time::now();
00086     point.point.x = x; point.point.y = y; point.point.z = z;
00087     goal.target = point;
00088 
00089     //we are pointing the high-def camera frame 
00090     //(pointing_axis defaults to X-axis)
00091     goal.pointing_frame = this->frame_to_point;
00092 
00093     //take at least 0.5 seconds to get there
00094     goal.min_duration = ros::Duration(1.0);
00095 
00096     //and go no faster than 1 rad/s
00097     goal.max_velocity = 0.25;
00098 
00099     //send the goal
00100     //point_head_client_.cancelAllGoals();
00101     point_head_client_.sendGoal(goal);
00102     ros::Time start = ros::Time::now();
00103     while(ros::ok() && !point_head_client_.waitForResult(ros::Duration(0.5))){
00104       if(start < (ros::Time::now() - ros::Duration(max_wait_seconds))
00105          || (ros::Time::now() - found_time_) < ros::Duration(5.0) )
00106       {
00107         break; //Waited too long or found goal meanwhile
00108       }
00109       ros::spinOnce();
00110     }
00111   }
00112 
00113   void searchAndSpin()
00114   {
00115     srand(10);
00116     float angle = 0.00;
00117     float door_width = 0.90;
00118     float handle_rel_to_marker_height = 0.20; 
00119     while (ros::ok())
00120     {
00121       ros::spinOnce();
00122       ros::Duration(1.0).sleep();
00123       if(!active_ || (ros::Time::now() - found_time_) < ros::Duration(5.0) )
00124         continue;
00125 
00126       lookAt("/door", door_width * cos(angle), door_width * sin(angle), handle_rel_to_marker_height);
00127       float tmp = ((rand() % 1000)/1000.0); // 0.0 to 1.0
00128       tmp *= tmp; //bias towards 0
00129       angle = tmp*45.0/180.*3.14159; //max angle 
00130       handle_rel_to_marker_height = ((rand() % 1000)/2000.0)-0.25; //rel height in the range -0.25 to +0.25
00131     }
00132   }
00133 
00134   bool switchActive(std_srvs::Empty::Request  &req,
00135                     std_srvs::Empty::Response &res )
00136   {
00137     active_ = true;
00138     ROS_INFO("Activated handle search");
00139     lookAt("/door", 0.9, 0.0, 0.20);
00140     
00141     return true;
00142   }
00143   bool switchInactive(std_srvs::Empty::Request  &req,
00144                       std_srvs::Empty::Response &res )
00145   {
00146     active_ = false;
00147     ROS_INFO("Deactivated handle search");
00148     return true;
00149   }
00150 };
00151 
00152 
00153 int main(int argc, char** argv)
00154 {
00155   //init the ROS node
00156   ros::init(argc, argv, "handle_search");
00157   
00158   RobotHead head;
00159   head.searchAndSpin();
00160   //ros::spin();
00161 }
00162 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


door_perception
Author(s): Felix Endres
autogenerated on Wed Dec 26 2012 16:03:53