Go to the documentation of this file.00001 #include "checkpoint_manager.h"
00002 #include <move_base_msgs/MoveBaseAction.h>
00003 #include <actionlib/client/simple_action_client.h>
00004 
00005 typedef actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> MoveBaseClient;
00006 
00007 CheckpointManager::CheckpointManager()
00008 {
00009     srv_checkpoint_ = nh_.advertiseService("add_nav_checkpoint",
00010                                            & CheckpointManager::add_checkpoint_callback, this);
00011 
00012     srv_action_ = nh_.advertiseService("action_checkpoint_nav",
00013                                            & CheckpointManager::action_callback, this);
00014 }
00015 
00016 bool
00017 CheckpointManager::add_checkpoint_callback(iri_checkpoint_nav::Checkpoint::Request  & req,
00018                                            iri_checkpoint_nav::Checkpoint::Response & res)
00019 {
00020     
00021     req.id = checkpoints_.size();
00022 
00023     checkpoints_.push_back(req);
00024     marker_.display_new_checkpoint(req);
00025 
00026     return true;
00027 }
00028 
00029 bool
00030 CheckpointManager::action_callback(iri_checkpoint_nav::ActionCheckpointNav::Request  & req,
00031                                    iri_checkpoint_nav::ActionCheckpointNav::Response & res)
00032 {
00033     switch (req.action)
00034     {
00035         case iri_checkpoint_nav::ActionCheckpointNav::Request::START_NAV:
00036             ROS_INFO("Recieved start navigation action");
00037             res.success = start_navigation();
00038             break;
00039         case iri_checkpoint_nav::ActionCheckpointNav::Request::RESET_CHECKPOINTS:
00040             ROS_INFO("Recieved reset action");
00041             reset_checkpoints();
00042             res.success = true;
00043             break;
00044         default:
00045             res.success = false;
00046     }
00047 
00048     return res.success;
00049 }
00050 
00051 void
00052 CheckpointManager::activate_current_checkpoint()
00053 {
00054     marker_.display_active_checkpoint(* current_goal_);
00055 }
00056 
00057 void
00058 CheckpointManager::visited_current_checkpoint()
00059 {
00060     marker_.display_visited_checkpoint(* current_goal_);
00061 }
00062 
00063 void
00064 CheckpointManager::reset_checkpoints()
00065 {
00066     checkpoints_.clear();
00067 }
00068 
00069 geometry_msgs::Quaternion
00070 CheckpointManager::generate_default_orientation()
00071 {
00072     geometry_msgs::Quaternion quat;
00073 
00074     quat.x = 0;
00075     quat.y = 0;
00076     quat.z = 0;
00077     quat.w = 1;
00078 
00079     return quat;
00080 }
00081 
00082 geometry_msgs::Quaternion
00083 CheckpointManager::generate_goal_orientation()
00084 {
00085     
00086     if ((current_goal_ == --checkpoints_.end()) && (current_goal_ == checkpoints_.begin()))
00087         return generate_default_orientation();
00088 
00089     std::vector<CheckpointRequest>::iterator ref_goal = current_goal_;
00090     CheckpointRequest start;
00091     CheckpointRequest end;
00092 
00093     if (current_goal_ == --checkpoints_.end()) {
00094         
00095         ref_goal--;
00096         start = * ref_goal;
00097         end   = * current_goal_;
00098     } else {
00099         
00100         ref_goal++;
00101         start = * current_goal_;
00102         end   = * ref_goal;
00103     }
00104 
00105     
00106     double rotation_angle = atan2(end.position.y - start.position.y,
00107                                   end.position.x - start.position.x);
00108 
00109     return tf::createQuaternionMsgFromYaw(rotation_angle);
00110 }
00111 
00112 bool
00113 CheckpointManager::send_navigation_goal(const CheckpointRequest checkpoint)
00114 {
00115     
00116     MoveBaseClient ac("move_base", true);
00117 
00118     
00119     while (! ac.waitForServer(ros::Duration(5.0))) {
00120         ROS_INFO("Waiting for the move_base action server to come up");
00121     }
00122 
00123     move_base_msgs::MoveBaseGoal goal;
00124 
00125     goal.target_pose.header.frame_id    = checkpoint.ref_frame;
00126     goal.target_pose.header.stamp       = ros::Time::now();
00127     goal.target_pose.pose.position      = checkpoint.position;
00128     goal.target_pose.pose.orientation   = generate_goal_orientation();
00129 
00130     ac.sendGoal(goal);
00131 
00132     ac.waitForResult();
00133 
00134     if (ac.getState() != actionlib::SimpleClientGoalState::SUCCEEDED) {
00135         ROS_WARN("The base failed to move");
00136         return false;
00137     }
00138 
00139     return true;
00140 }
00141 
00142 bool
00143 CheckpointManager::start_navigation()
00144 {
00145     std::vector<CheckpointRequest>::iterator it;
00146 
00147     for (it = checkpoints_.begin(); it < checkpoints_.end(); it++) {
00148         ROS_INFO("Sent navigation goal");
00149         current_goal_ = it;
00150         
00151         activate_current_checkpoint();
00152         
00153         if (! send_navigation_goal(* it))
00154             ROS_WARN("Navigation to the goal failed. Send to the next goal");
00155 
00156         visited_current_checkpoint();
00157     }
00158 
00159     return true;
00160 }
00161 
00162 int main(int argc, char** argv)
00163 {
00164     ros::init(argc, argv, "checkpoint_manager");
00165     CheckpointManager server;
00166 
00167     ros::spin();
00168 
00169     return 0;
00170 }