47 const std::string &action_name,
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);
264 if (!oscillation_timeout.
isZero())
272 else if (last_oscillation_reset + oscillation_timeout <
ros::Time::now())
278 controller_active =
false;
279 fillExePathResult(mbf_msgs::ExePathResult::OSCILLATION,
"Oscillation detected!", result);
280 goal_handle.setAborted(result, result.message);
289 controller_active =
false;
290 fillExePathResult(mbf_msgs::ExePathResult::SUCCESS,
"Controller succeeded; arrived at goal!", result);
291 goal_handle.setSucceeded(result, result.message);
296 controller_active =
false;
297 fillExePathResult(mbf_msgs::ExePathResult::INTERNAL_ERROR,
"Internal error: Unknown error thrown by the plugin!", result);
298 goal_handle.setAborted(result, result.message);
302 std::stringstream ss;
303 ss <<
"Internal error: Unknown state in a move base flex controller execution with the number: " 304 <<
static_cast<int>(state_moving_input);
307 goal_handle.setAborted(result, result.message);
308 controller_active =
false;
312 if (controller_active)
323 if (!controller_active)
335 GoalHandle &goal_handle,
336 uint32_t outcome,
const std::string &message,
337 const geometry_msgs::TwistStamped ¤t_twist)
339 mbf_msgs::ExePathFeedback feedback;
340 feedback.outcome = outcome;
341 feedback.message = message;
343 feedback.last_cmd_vel = current_twist;
344 if (feedback.last_cmd_vel.header.stamp.isZero())
350 goal_handle.publishFeedback(feedback);
354 uint32_t outcome,
const std::string &message,
355 mbf_msgs::ExePathResult &result)
357 result.outcome = outcome;
358 result.message = message;
void fillExePathResult(uint32_t outcome, const std::string &message, mbf_msgs::ExePathResult &result)
Utility method to fill the ExePath action result in a single line.
ControllerState
Internal states.
double angle(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
The controller has been stopped!
geometry_msgs::PoseStamped robot_pose_
Current robot pose.
Exceeded the maximum number of retries without a valid command.
Received no velocity command by the plugin, in the current cycle.
void run(GoalHandle &goal_handle, AbstractControllerExecution &execution)
Got a valid velocity command from the plugin.
The controller has been started without a plan.
boost::cv_status waitForStateUpdate(boost::chrono::microseconds const &duration)
std::string getMessage()
Gets the current plugin execution message.
The AbstractControllerExecution class loads and binds the controller plugin. It contains a thread run...
geometry_msgs::PoseStamped goal_pose_
Current goal pose.
virtual bool cancel()
Cancel the controller execution. This calls the cancel method of the controller plugin, sets the cancel_ flag to true, and waits for the control loop to stop. Normally called upon aborting the navigation.
Exceeded the patience time without a valid command.
#define ROS_FATAL_STREAM_NAMED(name, args)
bool isPatienceExceeded()
Checks whether the patience duration time has been exceeded, ot not.
Controller has been initialized successfully.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
#define ROS_WARN_STREAM_THROTTLE_NAMED(rate, name, args)
void start(GoalHandle &goal_handle, typename AbstractControllerExecution::Ptr execution_ptr)
Start controller action. Override abstract action version to allow updating current plan without stop...
The robot arrived the goal.
An internal error occurred.
Received an invalid plan that the controller plugin rejected.
geometry_msgs::TwistStamped getVelocityCmd()
Returns the last velocity command calculated by the plugin. Set by setVelocityCmd method...
void setNewPlan(const std::vector< geometry_msgs::PoseStamped > &plan, bool tolerance_from_action=false, double action_dist_tolerance=1.0, double action_angle_tolerance=3.1415)
Sets a new plan to the controller execution.
void publishExePathFeedback(GoalHandle &goal_handle, uint32_t outcome, const std::string &message, const geometry_msgs::TwistStamped ¤t_twist)
double distance(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
ControllerAction(const std::string &name, const mbf_utility::RobotInformation &robot_info)
ControllerState getState()
Return the current state of the controller execution. Thread communication safe.
#define ROS_INFO_STREAM(args)
boost::mutex goal_mtx_
lock goal handle for updating it while running
virtual bool start()
Starts the controller, a valid plan should be given in advance.
uint32_t getOutcome()
Gets the current plugin execution outcome.
Controller has been started.
#define ROS_WARN_STREAM_NAMED(name, args)
The controller has been canceled.