47 const std::string &action_name,
49 : AbstractActionBase(action_name, robot_info)
54 GoalHandle &goal_handle,
58 if(goal_handle.getGoalStatus().status == actionlib_msgs::GoalStatus::RECALLING)
60 goal_handle.setCanceled();
64 uint8_t slot = goal_handle.getGoal()->concurrency_slot;
66 bool update_plan =
false;
68 std::map<uint8_t, ConcurrencySlot>::iterator slot_it = concurrency_slots_.find(slot);
69 if(slot_it != concurrency_slots_.end() && slot_it->second.in_use)
71 boost::lock_guard<boost::mutex> goal_guard(
goal_mtx_);
72 if(slot_it->second.execution->getName() == goal_handle.getGoal()->controller ||
73 goal_handle.getGoal()->controller.empty())
79 execution_ptr = slot_it->second.execution;
80 execution_ptr->setNewPlan(goal_handle.getGoal()->path.poses,
81 goal_handle.getGoal()->tolerance_from_action,
82 goal_handle.getGoal()->dist_tolerance,
83 goal_handle.getGoal()->angle_tolerance);
85 goal_pose_ = goal_handle.getGoal()->path.poses.back();
86 mbf_msgs::ExePathResult result;
87 fillExePathResult(mbf_msgs::ExePathResult::CANCELED,
"Goal preempted by a new plan", result);
88 concurrency_slots_[slot].goal_handle.setCanceled(result, result.message);
89 concurrency_slots_[slot].goal_handle = goal_handle;
90 concurrency_slots_[slot].goal_handle.setAccepted();
93 slot_map_mtx_.unlock();
97 AbstractActionBase::start(goal_handle, execution_ptr);
105 uint8_t slot = goal_handle.getGoal()->concurrency_slot;
116 double oscillation_timeout_tmp;
117 private_nh.
param(
"oscillation_timeout", oscillation_timeout_tmp, 0.0);
120 double oscillation_distance;
121 private_nh.
param(
"oscillation_distance", oscillation_distance, 0.03);
123 mbf_msgs::ExePathResult result;
124 mbf_msgs::ExePathFeedback feedback;
127 bool controller_active =
true;
130 const mbf_msgs::ExePathGoal &goal = *(goal_handle.getGoal().get());
132 const std::vector<geometry_msgs::PoseStamped> &plan = goal.path.poses;
135 fillExePathResult(mbf_msgs::ExePathResult::INVALID_PATH,
"Controller started with an empty plan!", result);
136 goal_handle.setAborted(result, result.message);
138 controller_active =
false;
145 << name_ <<
"\" with plan:" << std::endl
146 <<
"frame: \"" << goal.path.header.frame_id <<
"\" " << std::endl
147 <<
"stamp: " << goal.path.header.stamp << std::endl
148 <<
"poses: " << goal.path.poses.size() << std::endl
149 <<
"goal: (" <<
goal_pose_.pose.position.x <<
", "
156 geometry_msgs::PoseStamped oscillation_pose;
159 bool first_cycle =
true;
161 while (controller_active &&
ros::ok())
167 controller_active =
false;
168 fillExePathResult(mbf_msgs::ExePathResult::TF_ERROR,
"Could not get the robot pose!", result);
170 goal_handle.setAborted(result, result.message);
183 state_moving_input = execution.
getState();
185 switch (state_moving_input)
188 execution.
setNewPlan(plan, goal.tolerance_from_action, goal.dist_tolerance, goal.angle_tolerance);
194 controller_active =
false;
195 result.outcome = mbf_msgs::ExePathResult::STOPPED;
196 result.message =
"Controller has been stopped!";
197 goal_handle.setAborted(result, result.message);
202 fillExePathResult(mbf_msgs::ExePathResult::CANCELED,
"Controller canceled", result);
203 goal_handle.setCanceled(result, result.message);
204 controller_active =
false;
214 ROS_INFO_STREAM(
"Try to cancel the plugin \"" << name_ <<
"\" after the patience time has been exceeded!");
217 ROS_INFO_STREAM(
"Successfully canceled the plugin \"" << name_ <<
"\" after the patience time has been exceeded!");
223 ROS_WARN_STREAM_NAMED(name_,
"The controller has been aborted after it exceeded the maximum number of retries!");
224 controller_active =
false;
226 goal_handle.setAborted(result, result.message);
231 controller_active =
false;
233 goal_handle.setAborted(result, result.message);
238 controller_active =
false;
239 fillExePathResult(mbf_msgs::ExePathResult::INVALID_PATH,
"Controller started without a path", result);
240 goal_handle.setAborted(result, result.message);
245 controller_active =
false;
246 fillExePathResult(mbf_msgs::ExePathResult::INVALID_PATH,
"Controller started with an empty plan", result);
247 goal_handle.setAborted(result, result.message);
252 controller_active =
false;
253 fillExePathResult(mbf_msgs::ExePathResult::INVALID_PATH,
"Controller started with an invalid plan", result);
254 goal_handle.setAborted(result, result.message);
260 controller_active = execution.
isMoving();
261 if (!controller_active)
264 goal_handle.setAborted(result, result.message);
274 if (!oscillation_timeout.
isZero())
282 else if (last_oscillation_reset + oscillation_timeout <
ros::Time::now())
288 controller_active =
false;
289 fillExePathResult(mbf_msgs::ExePathResult::OSCILLATION,
"Oscillation detected!", result);
290 goal_handle.setAborted(result, result.message);
299 controller_active =
false;
300 fillExePathResult(mbf_msgs::ExePathResult::SUCCESS,
"Controller succeeded; arrived at goal!", result);
301 goal_handle.setSucceeded(result, result.message);
306 controller_active =
false;
307 fillExePathResult(mbf_msgs::ExePathResult::INTERNAL_ERROR,
"Internal error: Unknown error thrown by the plugin!", result);
308 goal_handle.setAborted(result, result.message);
312 std::stringstream ss;
313 ss <<
"Internal error: Unknown state in a move base flex controller execution with the number: "
314 <<
static_cast<int>(state_moving_input);
317 goal_handle.setAborted(result, result.message);
318 controller_active =
false;
322 if (controller_active)
333 if (!controller_active)
345 GoalHandle &goal_handle,
346 uint32_t outcome,
const std::string &message,
347 const geometry_msgs::TwistStamped ¤t_twist)
349 mbf_msgs::ExePathFeedback feedback;
350 feedback.outcome = outcome;
351 feedback.message = message;
353 feedback.last_cmd_vel = current_twist;
354 if (feedback.last_cmd_vel.header.stamp.isZero())
360 goal_handle.publishFeedback(feedback);
364 uint32_t outcome,
const std::string &message,
365 mbf_msgs::ExePathResult &result)
367 result.outcome = outcome;
368 result.message = message;