00001 /************************************************************************************************** 00002 Software License Agreement (BSD License) 00003 00004 Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt 00005 All rights reserved. 00006 00007 Redistribution and use in source and binary forms, with or without modification, are permitted 00008 provided that the following conditions are met: 00009 00010 *Redistributions of source code must retain the above copyright notice, this list of 00011 conditions and the following disclaimer. 00012 *Redistributions in binary form must reproduce the above copyright notice, this list of 00013 conditions and the following disclaimer in the documentation and/or other materials provided 00014 with the distribution. 00015 *Neither the name of the University of Aveiro nor the names of its contributors may be used to 00016 endorse or promote products derived from this software without specific prior written permission. 00017 00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR 00019 IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND 00020 FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR 00021 CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 00022 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, 00023 DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER 00024 IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT 00025 OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00026 ***************************************************************************************************/ 00027 #include "ros/ros.h" 00028 #include "tf/tf.h" 00029 #include "leader_follower.h" 00030 00031 #define DEG2RAD 0.01745 00032 00033 00034 00035 /******* 00036 this node manages the choice of a leader and how the robot should follow it 00037 ********/ 00038 00039 void target_pose_callback(const nav_msgs::Odometry::ConstPtr& msg){ 00040 double distance_from_target = 2.0; 00041 double orientation = tf::getYaw(msg->pose.pose.orientation) + 1.57; 00042 double x_position = -msg->pose.pose.position.y - cos(orientation)*distance_from_target; 00043 double y_position = msg->pose.pose.position.x - sin(orientation)*distance_from_target; 00044 00045 ROS_INFO("x pos:%f, y pos:%f",x_position,y_position); 00046 00047 goal.target_pose.header.frame_id = "/map"; 00048 goal.target_pose.header.stamp = ros::Time::now(); 00049 00050 goal.target_pose.pose.position.x = x_position;//goal.target_pose.pose.position.x + 0.1;//-msg->pose.pose.position.y; 00051 goal.target_pose.pose.position.y = y_position;//goal.target_pose.pose.position.y + 0.1;//msg->pose.pose.position.x; 00052 goal.target_pose.pose.orientation = tf::createQuaternionMsgFromYaw(orientation); 00053 00054 } 00055 00056 void dyn_objects_callback(const trajectory_simulator::TrajectoryObservation::ConstPtr & dyn_objects){ 00057 00059 // candidate_[dyn_objects->object_id] = *dyn_objects; 00060 // ROS_INFO("received dyn_objects id:%d",dyn_objects->object_id); 00063 if(leader_id == dyn_objects->object_id && start_to_follow){ 00064 if(leader_path.poses.size() > 0){ 00065 //ROS_INFO("msg stamp:%d",dyn_objects->header.stamp.toSec()); 00066 //ROS_INFO("last path stamp:%d",leader_path.poses.back().header.stamp.toSec()); 00067 tlast = leader_path.poses.back().header.stamp.toSec(); 00068 tnow = ros::Time::now().toSec(); 00069 d = tnow - tlast; 00070 //ROS_INFO("elapsed time: %d",d); 00072 if(d > 2.0){ 00073 leader_pose.pose.position.x = dyn_objects->pose.x; 00074 leader_pose.pose.position.y = dyn_objects->pose.y; 00075 leader_pose.pose.orientation = tf::createQuaternionMsgFromYaw(dyn_objects->pose.theta + 1.57); 00076 leader_pose.header.stamp = ros::Time::now(); 00077 leader_path.poses.push_back(leader_pose); 00078 } 00079 } 00080 else{ 00082 path_initialized = true; 00083 leader_pose.pose.position.x = dyn_objects->pose.x; 00084 leader_pose.pose.position.y = dyn_objects->pose.y; 00085 leader_pose.pose.orientation = tf::createQuaternionMsgFromYaw(dyn_objects->pose.theta + 1.57); 00086 leader_pose.header.stamp = ros::Time::now(); 00087 leader_path.poses.push_back(leader_pose); 00088 } 00089 00091 // try{ 00092 // listener->waitForTransform("/robot_0/base_link", "/Hiro", ros::Time(0), ros::Duration(10.0)); 00093 // listener->lookupTransform("/robot_0/base_link", "/Hiro", ros::Time(0), transform); 00094 // // listener->lookupTransform("/robot_0/base_link", "/Hiro", ros::Time::now()/*(0)*/, transform); 00095 // // no_track_error=false; 00096 // } 00097 // catch (tf::TransformException ex){ 00098 // // cmd_vel.angular.z = 0; //if the kinect loose traking of the person, stop the wheelchair. 00099 // // cmd_vel.linear.x = 0; 00100 // // no_track_error=true; 00101 // ROS_ERROR("%s",ex.what()); 00102 // } 00103 00104 // ROS_INFO("robotx:%f,roboty:%f,objx:%f,objy:%f", 00105 // robot_pose.pose.pose.position.x, robot_pose.pose.pose.position.y, 00106 // dyn_objects->pose.x, dyn_objects->pose.y); 00107 // 00108 // dist = euclidean_dist( 00109 // robot_pose.pose.pose.position.x, robot_pose.pose.pose.position.y, 00110 // dyn_objects->pose.x, dyn_objects->pose.y); 00111 // 00112 // theta = atan2( 00113 // robot_pose.pose.pose.position.x - dyn_objects->pose.x, 00114 // robot_pose.pose.pose.position.y - dyn_objects->pose.y); 00115 // 00116 // //controller part 00117 // dist = sqrt(pow(transform.getOrigin().x(), 2) + pow(transform.getOrigin().y(), 2)); 00118 // theta = atan2(transform.getOrigin().y(),transform.getOrigin().x()); 00119 // 00120 // ROS_INFO("distance:%f, theta:%f",dist,theta); 00121 // if (dist>=dmin && dist<=dmax && theta>=-theta_max && theta<=theta_max) 00122 // { 00123 // cmd_vel.angular.z = 1.6 * (theta/theta_max) ; 00124 // cmd_vel.linear.x = 1.2 * (dist-dmin)/(dmax-dmin); 00125 // ROS_INFO("cmd ang:%f, cmd lin:%f",cmd_vel.angular.z,cmd_vel.linear.x); 00126 // robot_cmd_vel.publish(cmd_vel); 00127 // } 00128 // else 00129 // { 00130 // cmd_vel.angular.z = 0; 00131 // cmd_vel.linear.x = 0; 00132 // } 00133 } 00134 } 00135 00136 // void ar_pose_callback(const ar_pose::ARMarkers::ConstPtr& markers){ 00137 // //receives a list of marker and chooses a leader and send pose as goal 00138 // // num_markers = markers->markers.size(); 00139 // 00140 // num_markers = 1; 00141 // // ROS_INFO("number of markers: [%d]", num_markers); 00142 // 00143 // for(int i=0; i< num_markers; i++){ 00144 // 00145 // //feeding pose structure from ar_pose 00146 // source_pose.header = markers->markers[i].header; 00147 // source_pose.pose = markers->markers[i].pose.pose; 00148 // marker_id = markers->markers[i].id; 00149 // 00150 // ROS_INFO("before listener"); 00151 // //transform pose to /map frame 00152 // try{ 00153 // ros::Time now = ros::Time::now(); 00154 // listener->waitForTransform("/prosilica_optical_frame", "/map", source_pose.header.stamp, ros::Duration(10.0)); 00155 // // listener.waitForTransform("/usb_cam", "/map", source_pose.header.stamp, ros::Duration(10.0)); 00156 // listener->transformPose("/map",source_pose,target_pose); 00157 // } 00158 // catch (tf::TransformException ex) { 00159 // ROS_ERROR("%s", ex.what()); 00160 // return; 00161 // } 00162 // 00163 // goal.target_pose.header.frame_id = "/map"; 00164 // goal.target_pose.header.stamp = ros::Time::now(); 00165 // goal.target_pose.pose = target_pose.pose; 00166 // } 00167 // } 00168 00169 void leader_goal_callback(const geometry_msgs::PoseStamped::ConstPtr & msg){ 00170 // ROS_INFO("got leader goal pose"); 00171 // leader_goal = *msg; 00172 int temp_id = msg->pose.position.z; 00173 leader_goal[temp_id].pose = msg->pose; 00174 leader_goal[temp_id].header = msg->header; 00175 } 00176 00177 void robot_goal_callback(const geometry_msgs::PoseStamped::ConstPtr & msg){ 00178 // ROS_INFO("got robot goal pose"); 00179 // robot_goal = *msg; 00180 robot_goal.pose = msg->pose; 00181 robot_goal.header = msg->header; 00182 } 00183 00184 void robot_pose_callback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr & msg){ 00185 // ROS_INFO("got robot pose"); 00186 // robot_pose = *msg; 00187 robot_pose.pose = msg->pose; 00188 robot_pose.header = msg->header; 00189 } 00190 00191 int main(int argc, char **argv) 00192 { 00193 ros::init(argc, argv, "leader_follower"); 00194 ros::NodeHandle n; 00195 00196 //used in transformations 00197 tf::TransformListener _listener; 00198 listener = &_listener; 00199 00200 //initialize leader_path 00201 leader_path.header.stamp = ros::Time::now(); 00202 leader_path.header.frame_id = "/map"; 00203 00204 //tell the action client that we want to spin a thread by default 00205 // MoveBaseClient ac("robot_0/move_base", true); 00206 00207 //subscribers 00208 // pose_subscriber = n.subscribe("/robot_1/base_pose_ground_truth", 15, &target_pose_callback); 00209 // ar_pose_sub = n.subscribe("/ar_pose_marker", 15, &ar_pose_callback); 00210 dyn_objects_subscriber = n.subscribe("dynamic_objects", 100, &dyn_objects_callback); 00211 leader_goal_subscriber = n.subscribe("leader_goal_pose",10,&leader_goal_callback); 00212 robot_goal_subscriber = n.subscribe("/robot_0/goal", 1, &robot_goal_callback); 00213 robot_pose_subscriber = n.subscribe("/robot_0/amcl_pose", 1, &robot_pose_callback); 00214 00215 //publishers 00216 pathPublisher = n.advertise<nav_msgs::Path>("leader_path", 1); 00217 robot_cmd_vel = n.advertise<geometry_msgs::Twist>("/robot_0/cmd_vel",1); 00218 next_posePublisher = n.advertise<geometry_msgs::PoseStamped>("/robot_0/leader_next_pose", 1); 00219 00220 //wait for the action server to come up 00221 // while(!ac.waitForServer(ros::Duration(5.0))){ 00222 // ROS_INFO("Waiting for the move_base action server to come up"); 00223 // } 00224 00225 //initialize struct 00226 for(int i = 0; i < 4; i++){//number of markers 00227 leader_goal[i].pose.position.x = 99; 00228 leader_goal[i].pose.position.y = 99; 00229 } 00230 00231 ros::Rate loop_rate(10); 00232 00233 while (ros::ok()){ 00234 00236 robot2goal_distance = euclidean_dist( 00237 robot_pose.pose.pose.position.x,robot_pose.pose.pose.position.y, 00238 robot_goal.pose.position.x,robot_goal.pose.position.y); 00239 00241 if(leader_found){ 00242 leader2goal_distance = euclidean_dist( 00243 leader_pose.pose.position.x,leader_pose.pose.position.y, 00244 leader_goal[leader_id].pose.position.x,leader_goal[leader_id].pose.position.y); 00245 } 00246 // goals_distance = euclidean_dist( 00247 // candidate_[i].pose.position.x,candidate_[i].pose.position.y, 00248 // robot_goal.pose.position.x,robot_goal.pose.position.y); 00249 00250 // ROS_INFO("goal distances, robot:%.1f, leader:%f.1",robot2goal_distance,leader2goal_distance); 00252 for(int i = 0; i < 4; i++){//number of markers 00253 goals_distance = euclidean_dist( 00254 leader_goal[i].pose.position.x,leader_goal[i].pose.position.y, 00255 robot_goal.pose.position.x,robot_goal.pose.position.y); 00256 ROS_INFO("candidate id:%d, goals:%f",i,goals_distance); 00257 00259 //if(i == 0) goals_distance = 2; 00260 00261 if(goals_distance < 3.0){ 00262 // //candidate is a leader 00263 leader_found = true; 00264 if(leader_id != i){ 00265 leader_id = i; 00266 ROS_INFO("found new leader, id:%d",leader_id); 00267 //using z coordinate to obtain id 00268 path_initialized = false; 00269 start_to_follow = false; 00270 //initialize path structure 00271 leader_path.header.stamp = ros::Time::now(); 00272 leader_path.header.frame_id = "/map"; 00273 leader_path.poses.clear(); 00274 } 00275 //check if leader is closer to the goal than the robot is 00276 // ROS_INFO("leader2goal dist: %f, robot2goal dist: %f", leader2goal_distance, robot2goal_distance); 00277 if(/*leader2goal_distance > 1.0 && leader2goal_distance < 1.0*robot2goal_distance*/true){ 00278 ROS_INFO("leader %d is closer, start to follow",leader_id); 00279 start_to_follow = true; 00280 } 00281 break; //can skip candidate search as leader has been found 00282 } 00283 } 00284 00285 //leader decision part 00286 // if(goals_distance < 5.0){ 00287 // if(leader_found){ 00288 // //leader found 00289 // if(leader_id != leader_goal.pose.position.z){ ///check if it is a new leader 00290 // ROS_INFO("found leader, id:%d",leader_id); 00291 // //using z coordinate to obtain id 00292 // leader_id = leader_goal.pose.position.z; 00293 // path_initialized = false; 00294 // start_to_follow = false; 00295 // //initialize path structure 00296 // leader_path.header.stamp = ros::Time::now(); 00297 // leader_path.header.frame_id = "/map"; 00298 // leader_path.poses.clear(); 00299 // } 00300 // //check if leader is closer to the goal than the robot is 00301 // ROS_INFO("leader2goal dist: %f, robot2goal dist: %f", leader2goal_distance, robot2goal_distance); 00302 // if(leader2goal_distance > 1.0 && leader2goal_distance < 1.0*robot2goal_distance){ 00303 // ROS_INFO("leader is closer, start to follow"); 00304 // start_to_follow = true; 00305 // } 00306 // } 00307 00308 if(path_initialized){ 00309 if(send_goal){ 00311 goal.target_pose.header.frame_id = "/map"; 00312 goal.target_pose.header.stamp = ros::Time::now(); 00313 goal.target_pose.pose.position.x = leader_path.poses[0].pose.position.x; 00314 goal.target_pose.pose.position.y = leader_path.poses[0].pose.position.y; 00315 goal.target_pose.pose.orientation = leader_path.poses[0].pose.orientation; 00316 00318 next_pose.header.frame_id = "/map"; 00319 next_pose.header.stamp = ros::Time::now(); 00320 next_pose.pose = goal.target_pose.pose; 00321 next_posePublisher.publish(next_pose); 00322 00323 ROS_INFO("Sending goal"); 00324 // ac.sendGoal(goal); 00325 send_goal = false; 00326 } 00327 00328 // ROS_INFO("robotx:%f,roboty:%f,goalx:%f,goaly:%f", 00329 // robot_pose.pose.pose.position.x, robot_pose.pose.pose.position.y, 00330 // leader_path.poses[0].pose.position.x, leader_path.poses[0].pose.position.y); 00331 00333 double distance_to_pose = euclidean_dist( 00334 robot_pose.pose.pose.position.x, robot_pose.pose.pose.position.y, 00335 goal.target_pose.pose.position.x, goal.target_pose.pose.position.y); 00336 // ROS_INFO("ROBOT DISTANCE TO GOAL: %f", distance_to_pose); 00337 00339 // if(ac.getState() == actionlib::SimpleClientGoalState::SUCCEEDED){ 00340 if(distance_to_pose < 2.0){ 00341 if(leader_path.poses.size() > 1){ 00342 leader_path.poses.erase(leader_path.poses.begin()); 00343 send_goal = true; 00344 } 00345 } 00346 } 00347 00348 pathPublisher.publish(leader_path); 00349 ros::spinOnce(); 00350 loop_rate.sleep(); 00351 00352 00353 } 00354 return 0; 00355 } 00356