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
00038
00039
00040
00041 #include "mbf_abstract_nav/controller_action.h"
00042
00043 namespace mbf_abstract_nav{
00044
00045
00046 ControllerAction::ControllerAction(
00047 const std::string &action_name,
00048 const RobotInformation &robot_info)
00049 : AbstractAction(action_name, robot_info, boost::bind(&mbf_abstract_nav::ControllerAction::run, this, _1, _2))
00050 {
00051 }
00052
00053 void ControllerAction::start(
00054 GoalHandle &goal_handle,
00055 typename AbstractControllerExecution::Ptr execution_ptr
00056 )
00057 {
00058 if(goal_handle.getGoalStatus().status == actionlib_msgs::GoalStatus::RECALLING)
00059 {
00060 goal_handle.setCanceled();
00061 return;
00062 }
00063
00064 uint8_t slot = goal_handle.getGoal()->concurrency_slot;
00065
00066 bool update_plan = false;
00067 slot_map_mtx_.lock();
00068 std::map<uint8_t, ConcurrencySlot>::iterator slot_it = concurrency_slots_.find(slot);
00069 if(slot_it != concurrency_slots_.end())
00070 {
00071 boost::lock_guard<boost::mutex> goal_guard(goal_mtx_);
00072 if(slot_it->second.execution->getName() == goal_handle.getGoal()->controller ||
00073 goal_handle.getGoal()->controller.empty())
00074 {
00075 update_plan = true;
00076
00077
00078 execution_ptr = slot_it->second.execution;
00079 execution_ptr->setNewPlan(goal_handle.getGoal()->path.poses);
00080 mbf_msgs::ExePathResult result;
00081 fillExePathResult(mbf_msgs::ExePathResult::CANCELED, "Goal preempted by a new plan", result);
00082 concurrency_slots_[slot].goal_handle.setCanceled(result, result.message);
00083 concurrency_slots_[slot].goal_handle = goal_handle;
00084 concurrency_slots_[slot].goal_handle.setAccepted();
00085 }
00086 }
00087 slot_map_mtx_.unlock();
00088 if(!update_plan)
00089 {
00090
00091 AbstractAction::start(goal_handle, execution_ptr);
00092 }
00093 }
00094
00095 void ControllerAction::run(GoalHandle &goal_handle, AbstractControllerExecution &execution)
00096 {
00097 goal_mtx_.lock();
00098
00099 uint8_t slot = goal_handle.getGoal()->concurrency_slot;
00100 goal_mtx_.unlock();
00101
00102 ROS_DEBUG_STREAM_NAMED(name_, "Start action " << name_);
00103
00104
00105 goal_pose_ = geometry_msgs::PoseStamped();
00106 robot_pose_ = geometry_msgs::PoseStamped();
00107
00108 ros::NodeHandle private_nh("~");
00109
00110 double oscillation_timeout_tmp;
00111 private_nh.param("oscillation_timeout", oscillation_timeout_tmp, 0.0);
00112 ros::Duration oscillation_timeout(oscillation_timeout_tmp);
00113
00114 double oscillation_distance;
00115 private_nh.param("oscillation_distance", oscillation_distance, 0.03);
00116
00117 mbf_msgs::ExePathResult result;
00118 mbf_msgs::ExePathFeedback feedback;
00119
00120 typename AbstractControllerExecution::ControllerState state_moving_input;
00121 bool controller_active = true;
00122
00123 goal_mtx_.lock();
00124 const mbf_msgs::ExePathGoal &goal = *(goal_handle.getGoal().get());
00125
00126 const std::vector<geometry_msgs::PoseStamped> &plan = goal.path.poses;
00127 if (plan.empty())
00128 {
00129 fillExePathResult(mbf_msgs::ExePathResult::INVALID_PATH, "Controller started with an empty plan!", result);
00130 goal_handle.setAborted(result, result.message);
00131 ROS_ERROR_STREAM_NAMED(name_, result.message << " Canceling the action call.");
00132 controller_active = false;
00133 }
00134
00135 goal_pose_ = plan.back();
00136 ROS_DEBUG_STREAM_NAMED(name_, "Called action \""
00137 << name_ << "\" with plan:" << std::endl
00138 << "frame: \"" << goal.path.header.frame_id << "\" " << std::endl
00139 << "stamp: " << goal.path.header.stamp << std::endl
00140 << "poses: " << goal.path.poses.size() << std::endl
00141 << "goal: (" << goal_pose_.pose.position.x << ", "
00142 << goal_pose_.pose.position.y << ", "
00143 << goal_pose_.pose.position.z << ")");
00144
00145 goal_mtx_.unlock();
00146
00147
00148 geometry_msgs::PoseStamped oscillation_pose;
00149 ros::Time last_oscillation_reset = ros::Time::now();
00150
00151 bool first_cycle = true;
00152
00153 while (controller_active && ros::ok())
00154 {
00155
00156
00157 if (!robot_info_.getRobotPose(robot_pose_))
00158 {
00159 controller_active = false;
00160 fillExePathResult(mbf_msgs::ExePathResult::TF_ERROR, "Could not get the robot pose!", result);
00161 goal_mtx_.lock();
00162 goal_handle.setAborted(result, result.message);
00163 goal_mtx_.unlock();
00164 ROS_ERROR_STREAM_NAMED(name_, result.message << " Canceling the action call.");
00165 break;
00166 }
00167
00168 if (first_cycle)
00169 {
00170
00171 oscillation_pose = robot_pose_;
00172 }
00173
00174 goal_mtx_.lock();
00175 state_moving_input = execution.getState();
00176
00177 switch (state_moving_input)
00178 {
00179 case AbstractControllerExecution::INITIALIZED:
00180 execution.setNewPlan(plan);
00181 execution.start();
00182 break;
00183
00184 case AbstractControllerExecution::STOPPED:
00185 ROS_WARN_STREAM_NAMED(name_, "The controller has been stopped!");
00186 controller_active = false;
00187 break;
00188
00189 case AbstractControllerExecution::CANCELED:
00190 ROS_INFO_STREAM("Action \"exe_path\" canceled");
00191 fillExePathResult(mbf_msgs::ExePathResult::CANCELED, "Controller canceled", result);
00192 goal_handle.setCanceled(result, result.message);
00193 controller_active = false;
00194 break;
00195
00196 case AbstractControllerExecution::STARTED:
00197 ROS_DEBUG_STREAM_NAMED(name_, "The moving has been started!");
00198 break;
00199
00200
00201 case AbstractControllerExecution::PLANNING:
00202 if (execution.isPatienceExceeded())
00203 {
00204 ROS_DEBUG_STREAM_NAMED(name_, "The controller patience has been exceeded! Stopping controller...");
00205
00206
00207
00208
00209
00210
00211 execution.stop();
00212 }
00213 break;
00214
00215 case AbstractControllerExecution::MAX_RETRIES:
00216 ROS_WARN_STREAM_NAMED(name_, "The controller has been aborted after it exceeded the maximum number of retries!");
00217 controller_active = false;
00218 fillExePathResult(execution.getOutcome(), execution.getMessage(), result);
00219 goal_handle.setAborted(result, result.message);
00220 break;
00221
00222 case AbstractControllerExecution::PAT_EXCEEDED:
00223 ROS_WARN_STREAM_NAMED(name_, "The controller has been aborted after it exceeded the patience time");
00224 controller_active = false;
00225 fillExePathResult(mbf_msgs::ExePathResult::PAT_EXCEEDED, execution.getMessage(), result);
00226 goal_handle.setAborted(result, result.message);
00227 break;
00228
00229 case AbstractControllerExecution::NO_PLAN:
00230 ROS_WARN_STREAM_NAMED(name_, "The controller has been started without a plan!");
00231 controller_active = false;
00232 fillExePathResult(mbf_msgs::ExePathResult::INVALID_PATH, "Controller started without a path", result);
00233 goal_handle.setAborted(result, result.message);
00234 break;
00235
00236 case AbstractControllerExecution::EMPTY_PLAN:
00237 ROS_WARN_STREAM_NAMED(name_, "The controller has received an empty plan");
00238 controller_active = false;
00239 fillExePathResult(mbf_msgs::ExePathResult::INVALID_PATH, "Controller started with an empty plan", result);
00240 goal_handle.setAborted(result, result.message);
00241 break;
00242
00243 case AbstractControllerExecution::INVALID_PLAN:
00244 ROS_WARN_STREAM_NAMED(name_, "The controller has received an invalid plan");
00245 controller_active = false;
00246 fillExePathResult(mbf_msgs::ExePathResult::INVALID_PATH, "Controller started with an invalid plan", result);
00247 goal_handle.setAborted(result, result.message);
00248 break;
00249
00250 case AbstractControllerExecution::NO_LOCAL_CMD:
00251 ROS_WARN_STREAM_THROTTLE_NAMED(3, name_, "No velocity command received from controller! "
00252 << execution.getMessage());
00253 publishExePathFeedback(goal_handle, execution.getOutcome(), execution.getMessage(), execution.getVelocityCmd());
00254 break;
00255
00256 case AbstractControllerExecution::GOT_LOCAL_CMD:
00257 if (!oscillation_timeout.isZero())
00258 {
00259
00260 if (mbf_utility::distance(robot_pose_, oscillation_pose) >= oscillation_distance)
00261 {
00262 last_oscillation_reset = ros::Time::now();
00263 oscillation_pose = robot_pose_;
00264 }
00265 else if (last_oscillation_reset + oscillation_timeout < ros::Time::now())
00266 {
00267 ROS_WARN_STREAM_NAMED(name_, "The controller is oscillating for "
00268 << (ros::Time::now() - last_oscillation_reset).toSec() << "s");
00269 execution.stop();
00270 controller_active = false;
00271 fillExePathResult(mbf_msgs::ExePathResult::OSCILLATION, "Oscillation detected!", result);
00272 goal_handle.setAborted(result, result.message);
00273 break;
00274 }
00275 }
00276 publishExePathFeedback(goal_handle, execution.getOutcome(), execution.getMessage(), execution.getVelocityCmd());
00277 break;
00278
00279 case AbstractControllerExecution::ARRIVED_GOAL:
00280 ROS_DEBUG_STREAM_NAMED(name_, "Controller succeeded; arrived to goal");
00281 controller_active = false;
00282 fillExePathResult(mbf_msgs::ExePathResult::SUCCESS, "Controller succeeded; arrived to goal!", result);
00283 goal_handle.setSucceeded(result, result.message);
00284 break;
00285
00286 case AbstractControllerExecution::INTERNAL_ERROR:
00287 ROS_FATAL_STREAM_NAMED(name_, "Internal error: Unknown error thrown by the plugin: " << execution.getMessage());
00288 controller_active = false;
00289 fillExePathResult(mbf_msgs::ExePathResult::INTERNAL_ERROR, "Internal error: Unknown error thrown by the plugin!", result);
00290 goal_handle.setAborted(result, result.message);
00291 break;
00292
00293 default:
00294 std::stringstream ss;
00295 ss << "Internal error: Unknown state in a move base flex controller execution with the number: "
00296 << static_cast<int>(state_moving_input);
00297 fillExePathResult(mbf_msgs::ExePathResult::INTERNAL_ERROR, ss.str(), result);
00298 ROS_FATAL_STREAM_NAMED(name_, result.message);
00299 goal_handle.setAborted(result, result.message);
00300 controller_active = false;
00301 }
00302 goal_mtx_.unlock();
00303
00304 if (controller_active)
00305 {
00306
00307
00308
00309 execution.waitForStateUpdate(boost::chrono::milliseconds(500));
00310 }
00311
00312 first_cycle = false;
00313 }
00314
00315 if (!controller_active)
00316 {
00317 ROS_DEBUG_STREAM_NAMED(name_, "\"" << name_ << "\" action ended properly.");
00318 }
00319 else
00320 {
00321
00322 ROS_DEBUG_STREAM_NAMED(name_, "\"" << name_ << "\" action has been stopped!");
00323 }
00324 }
00325
00326 void ControllerAction::publishExePathFeedback(
00327 GoalHandle& goal_handle,
00328 uint32_t outcome, const std::string &message,
00329 const geometry_msgs::TwistStamped& current_twist)
00330 {
00331 mbf_msgs::ExePathFeedback feedback;
00332 feedback.outcome = outcome;
00333 feedback.message = message;
00334
00335 feedback.last_cmd_vel = current_twist;
00336 if (feedback.last_cmd_vel.header.stamp.isZero())
00337 feedback.last_cmd_vel.header.stamp = ros::Time::now();
00338
00339 feedback.current_pose = robot_pose_;
00340 feedback.dist_to_goal = static_cast<float>(mbf_utility::distance(robot_pose_, goal_pose_));
00341 feedback.angle_to_goal = static_cast<float>(mbf_utility::angle(robot_pose_, goal_pose_));
00342 goal_handle.publishFeedback(feedback);
00343 }
00344
00345 void ControllerAction::fillExePathResult(
00346 uint32_t outcome, const std::string &message,
00347 mbf_msgs::ExePathResult &result)
00348 {
00349 result.outcome = outcome;
00350 result.message = message;
00351 result.final_pose = robot_pose_;
00352 result.dist_to_goal = static_cast<float>(mbf_utility::distance(robot_pose_, goal_pose_));
00353 result.angle_to_goal = static_cast<float>(mbf_utility::angle(robot_pose_, goal_pose_));
00354 }
00355
00356 }
00357