00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <door_handle_detector/DoorsDetectorCloud.h>
00038 #include <door_handle_detector/DoorsDetector.h>
00039 #include <pr2_doors_common/door_functions.h>
00040 #include <door_msgs/Door.h>
00041 #include <boost/thread/thread.hpp>
00042 #include <pr2_laser_snapshotter/BuildCloudAngle.h>
00043 #include <kdl/frames.hpp>
00044
00045 #include <pr2_controllers_msgs/PointHeadActionGoal.h>
00046 #include "pr2_doors_actions/action_detect_handle.h"
00047
00048
00049 using namespace ros;
00050 using namespace std;
00051 using namespace door_handle_detector;
00052 using namespace pr2_doors_common;
00053 using namespace KDL;
00054 using namespace actionlib;
00055
00056 static const string fixed_frame = "odom_combined";
00057 static const double scan_speed = 0.1;
00058 static const double scan_height = 0.4;
00059 static const unsigned int max_retries = 5;
00060 static const double handle_dimension = 0.07;
00061
00062 DetectHandleAction::DetectHandleAction(tf::TransformListener& tf):
00063 tf_(tf),
00064 action_server_(ros::NodeHandle(),
00065 "detect_handle",
00066 boost::bind(&DetectHandleAction::execute, this, _1)),
00067 laserSnapshotActionClient_("point_cloud_action/single_sweep_cloud")
00068 {
00069 NodeHandle node;
00070 pub_ = node.advertise<pr2_controllers_msgs::PointHeadActionGoal>("head_traj_controller/point_head_action/goal",10);
00071 };
00072
00073
00074 DetectHandleAction::~DetectHandleAction()
00075 {
00076 };
00077
00078
00079
00080 void DetectHandleAction::execute(const door_msgs::DoorGoalConstPtr& goal)
00081 {
00082 ROS_INFO("DetectHandleAction: execute");
00083
00084
00085 door_msgs::Door goal_tr;
00086 transformTo(tf_, fixed_frame, goal->door, goal_tr, fixed_frame);
00087
00088
00089 for (unsigned int nr_tries=0; nr_tries<max_retries; nr_tries++){
00090
00091
00092 if (action_server_.isPreemptRequested()){
00093 ROS_INFO("DetectHandleAction: Preempted");
00094 action_server_.setPreempted();
00095 return;
00096 }
00097
00098 boost::thread* thread_laser;
00099 bool success_laser, success_camera;
00100 door_msgs::Door result_laser, result_camera;
00101 thread_laser = new boost::thread(boost::bind(&DetectHandleAction::laserDetectionFunction, this, goal_tr, &result_laser, &success_laser));
00102
00103 thread_laser->join();
00104
00105 delete thread_laser;
00106
00107 result_camera = result_laser;
00108 success_camera = success_laser;
00109
00110 ROS_INFO("Laser success %i, Camera success %i", success_laser, success_camera);
00111
00112 if (!success_laser && !success_camera){
00113 ROS_ERROR("Laser and Camera detection failed");
00114 continue;
00115 }
00116 if (!success_laser){
00117 ROS_ERROR("Laser detection failed");
00118 continue;
00119 }
00120 if (!success_camera){
00121 ROS_ERROR("Camera detection failed");
00122 continue;
00123 }
00124
00125
00126 if (!transformTo(tf_, fixed_frame, result_laser, result_laser, fixed_frame)){
00127 ROS_ERROR ("Could not transform laser door message from frame %s to frame %s.",
00128 result_laser.header.frame_id.c_str (), fixed_frame.c_str ());
00129 action_server_.setAborted();
00130 return;
00131 }
00132 ROS_INFO("detected handle position transformed to '%s'", fixed_frame.c_str());
00133
00134
00135 if (!transformTo(tf_, fixed_frame, result_camera, result_camera, fixed_frame)){
00136 ROS_ERROR ("Could not transform camera door message from frame %s to frame %s.",
00137 result_camera.header.frame_id.c_str (), fixed_frame.c_str ());
00138 action_server_.setAborted();
00139 return;
00140 }
00141 ROS_INFO("detected handle position transformed to '%s'", fixed_frame.c_str());
00142
00143
00144 double error = sqrt(pow(result_laser.handle.x - result_camera.handle.x,2) +
00145 pow(result_laser.handle.y - result_camera.handle.y,2) +
00146 pow(result_laser.handle.z - result_camera.handle.z,2));
00147 ROS_INFO("difference between laser and camera result = %f", error);
00148 if (error < this->handle_laser_camera_distance_tol){
00149
00150 action_result_.door = result_laser;
00151 action_result_.door.handle.x = (result_laser.handle.x + result_camera.handle.x)/2.0;
00152 action_result_.door.handle.y = (result_laser.handle.y + result_camera.handle.y)/2.0;
00153 action_result_.door.handle.z = (result_laser.handle.z + result_camera.handle.z)/2.0;
00154
00155
00156 geometry_msgs::Point32 handle_robot_point;
00157 if (!transformPointTo(tf_, action_result_.door.header.frame_id, "base_footprint", action_result_.door.header.stamp, action_result_.door.handle, handle_robot_point, fixed_frame, action_result_.door.header.stamp)){
00158 ROS_ERROR ("Could not transform handle from frame %s to frame %s.",
00159 action_result_.door.header.frame_id.c_str (), string("base_footprint").c_str ());
00160 action_server_.setAborted();
00161 return;
00162 }
00163 geometry_msgs::Vector3 handle_robot_vec;
00164 handle_robot_vec.x = handle_robot_point.x;
00165 handle_robot_vec.y = handle_robot_point.y;
00166 handle_robot_vec.z = handle_robot_point.z;
00167 if (!transformVectorTo(tf_,"base_footprint", action_result_.door.header.frame_id, action_result_.door.header.stamp, handle_robot_vec, handle_robot_vec, fixed_frame, action_result_.door.header.stamp)){
00168 ROS_ERROR ("Could not transform handle from frame %s to frame %s.",
00169 action_result_.door.header.frame_id.c_str (), string("base_footprint").c_str ());
00170 action_server_.setAborted();
00171 return;
00172 }
00173 Vector handle_door(handle_robot_vec.x, handle_robot_vec.y, 0.0);
00174 handle_door.Normalize();
00175 Vector door_normal = getDoorNormal(action_result_.door);
00176 Vector handle_door_old = - handle_door * handle_dimension;
00177 Vector handle_door_new = Rotation::RotZ(getVectorAngle(handle_door, door_normal)) * handle_door_old;
00178 Vector handle(action_result_.door.handle.x, action_result_.door.handle.y, action_result_.door.handle.z);
00179 handle = handle - handle_door_old + handle_door_new;
00180 action_result_.door.handle.x = handle.x();
00181 action_result_.door.handle.y = handle.y();
00182 action_result_.door.handle.z = handle.z();
00183
00184 ROS_INFO("Found handle in %i tries", nr_tries+1);
00185 action_result_.door = result_laser;
00186 action_server_.setSucceeded(action_result_);
00187 return;
00188 }
00189 else
00190 {
00191 ROS_WARN("Distance between laser and camera handle detection is more than %f m apart",this->handle_laser_camera_distance_tol);
00192 ROS_WARN(" laser results: x = %f y = %f z = %f ", result_laser.handle.x, result_laser.handle.y, result_laser.handle.z);
00193 ROS_WARN(" camera results: x = %f y = %f z = %f ", result_camera.handle.x, result_camera.handle.y, result_camera.handle.z);
00194 ROS_WARN("Retrying handle detection");
00195 }
00196 }
00197 ROS_ERROR("Did not find hanlde in %i tries", max_retries);
00198 action_server_.setAborted();
00199 }
00200
00201
00202
00203 void DetectHandleAction::laserDetectionFunction(const door_msgs::Door& door_in,
00204 door_msgs::Door* door_out, bool* success)
00205 {
00206 *success = laserDetection(door_in, *door_out);
00207 }
00208
00209 bool DetectHandleAction::laserDetection(const door_msgs::Door& door_in,
00210 door_msgs::Door& door_out)
00211 {
00212
00213 if (!tf_.waitForTransform("base_footprint", "laser_tilt_link", ros::Time(), ros::Duration().fromSec(5.0))){
00214 ROS_ERROR("could not get transform from 'base_footprint' to 'laser_tilt_link'");
00215 return false;
00216 }
00217 tf::StampedTransform tilt_stage;
00218 tf_.lookupTransform("base_footprint", "laser_tilt_link", ros::Time(), tilt_stage);
00219 ROS_INFO("handle activate");
00220 double laser_height = tilt_stage.getOrigin()[2];
00221 tf::Stamped<tf::Vector3> handlepoint(tf::Vector3((door_in.door_p1.x+door_in.door_p2.x)/2.0,
00222 (door_in.door_p1.y+door_in.door_p2.y)/2.0,
00223 0.9),
00224 ros::Time(), door_in.header.frame_id);
00225 if (!tf_.waitForTransform("base_footprint", handlepoint.frame_id_, ros::Time(), ros::Duration().fromSec(5.0))){
00226 ROS_ERROR("could not get transform from 'base_footprint' to '%s'", handlepoint.frame_id_.c_str());
00227 return false;
00228 }
00229 tf_.transformPoint("base_footprint", handlepoint, handlepoint);
00230 double handle_bottom = handlepoint[2]-(scan_height/2.0);
00231 double handle_top = handlepoint[2]+(scan_height/2.0);
00232 handlepoint[2] = 0;
00233 double dist = handlepoint.length();
00234 ROS_INFO("tilt laser is at height %f, and door at distance %f", laser_height, dist);
00235
00236
00237
00238 NodeHandle node;
00239 bool use_sim_time;
00240 node.param("use_sim_time", use_sim_time, false);
00241 if (!use_sim_time){
00242 ROS_WARN("dynamic_reconfigure of tilt_hokuyo_node is commented out, awaiting #3894 from simulation");
00243 system("rosrun dynamic_reconfigure dynparam set /tilt_hokuyo_node '{ intensity: true }'");
00244 system("rosrun dynamic_reconfigure dynparam set /tilt_hokuyo_node '{ skip: 1 }'");
00245 }
00246
00247
00248 if (action_server_.isPreemptRequested()) return false;
00249
00250 ROS_INFO("get a point cloud from the door");
00251 pr2_laser_snapshotter::TiltLaserSnapshotGoal goalMsg;
00252
00253 laserSnapshotActionClient_.waitForServer();
00254
00255 goalMsg.angle_begin = -atan2(handle_top - laser_height, dist);
00256 goalMsg.angle_end =atan2(laser_height - handle_bottom, dist);
00257 goalMsg.duration = scan_height/scan_speed;
00258
00259 laserSnapshotActionClient_.sendGoal(goalMsg);
00260 laserSnapshotActionClient_.waitForResult();
00261
00262 if (laserSnapshotActionClient_.getState() != actionlib::SimpleClientGoalState::SUCCEEDED)
00263 {
00264 ROS_ERROR("DetectHandleAction: failed to get point cloud for handle detection");
00265 return false;
00266 }
00267 pr2_laser_snapshotter::TiltLaserSnapshotResultConstPtr res_pointcloud = laserSnapshotActionClient_.getResult();
00268
00269
00270 if (action_server_.isPreemptRequested()) return false;
00271 ROS_INFO("start detecting the handle using the laser, in a pointcloud of size %u", (unsigned int)res_pointcloud->cloud.points.size());
00272 door_handle_detector::DoorsDetectorCloud::Request req_handledetect;
00273 door_handle_detector::DoorsDetectorCloud::Response res_handledetect;
00274 req_handledetect.door = door_in;
00275 req_handledetect.cloud = res_pointcloud->cloud;
00276 if (!ros::service::call("handle_detector_cloud", req_handledetect, res_handledetect)){
00277 ROS_ERROR("failed to detect a handle using the laser");
00278 return false;
00279 }
00280
00281 door_out = res_handledetect.doors[0];
00282 return true;
00283 }
00284
00285
00286 void DetectHandleAction::cameraDetectionFunction(const door_msgs::Door& door_in,
00287 door_msgs::Door* door_out, bool* success)
00288 {
00289 *success = cameraDetection(door_in, *door_out);
00290 }
00291
00292
00293 bool DetectHandleAction::cameraDetection(const door_msgs::Door& door_in,
00294 door_msgs::Door& door_out)
00295 {
00296
00297 ROS_INFO("point head towards door");
00298 pr2_controllers_msgs::PointHeadGoal head_goal;
00299 head_goal.pointing_axis.x = 1;
00300 head_goal.pointing_axis.y = 0;
00301 head_goal.pointing_axis.z = 0;
00302 head_goal.pointing_frame = "head_tilt_link";
00303 head_goal.min_duration = ros::Duration(0.0);
00304 head_goal.max_velocity = 10.0;
00305
00306 geometry_msgs::PointStamped door_pnt;
00307 door_pnt.point.z = 0.9;
00308 door_pnt.header.frame_id = door_in.header.frame_id;
00309 if (door_in.hinge == door_in.HINGE_P1){
00310 door_pnt.point.x = 0.1*door_in.door_p1.x + 0.9*door_in.door_p2.x;
00311 door_pnt.point.y = 0.1*door_in.door_p1.y + 0.9*door_in.door_p2.y;
00312 }
00313 else if (door_in.hinge == door_in.HINGE_P2){
00314 door_pnt.point.x = 0.9*door_in.door_p1.x + 0.1*door_in.door_p2.x;
00315 door_pnt.point.y = 0.9*door_in.door_p1.y + 0.1*door_in.door_p2.y;
00316 }
00317 else{
00318 ROS_ERROR("Door hinge side is not specified");
00319 return false;
00320 }
00321 cout << "door_pnt.point " << door_in.header.frame_id << " "
00322 << door_pnt.point.x << " "
00323 << door_pnt.point.y << " "
00324 << door_pnt.point.z << endl;
00325 head_goal.target = door_pnt;
00326
00327 pr2_controllers_msgs::PointHeadActionGoal head_goal_action;
00328 head_goal_action.goal = head_goal;
00329 pub_.publish(head_goal_action);
00330 ros::Duration().fromSec(2).sleep();
00331
00332
00333 if (action_server_.isPreemptRequested()) return false;
00334 ROS_INFO("start detecting the handle using the camera");
00335 door_handle_detector::DoorsDetector::Request req_handledetect;
00336 door_handle_detector::DoorsDetector::Response res_handledetect;
00337 req_handledetect.door = door_in;
00338 if (!ros::service::call("door_handle_vision_detector", req_handledetect, res_handledetect)){
00339 ROS_ERROR("failed to detect a handle using the camera");
00340 return false;
00341 }
00342
00343 door_out = res_handledetect.doors[0];
00344 return true;
00345 }