47 const std::string &action_name,
58 if(goal_handle.
getGoalStatus().status == actionlib_msgs::GoalStatus::RECALLING)
64 uint8_t slot = goal_handle.
getGoal()->concurrency_slot;
66 bool update_plan =
false;
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())
78 execution_ptr = slot_it->second.execution;
79 execution_ptr->setNewPlan(goal_handle.
getGoal()->path.poses);
80 mbf_msgs::ExePathResult result;
81 fillExePathResult(mbf_msgs::ExePathResult::CANCELED,
"Goal preempted by a new plan", result);
99 uint8_t slot = goal_handle.
getGoal()->concurrency_slot;
110 double oscillation_timeout_tmp;
111 private_nh.
param(
"oscillation_timeout", oscillation_timeout_tmp, 0.0);
114 double oscillation_distance;
115 private_nh.
param(
"oscillation_distance", oscillation_distance, 0.03);
117 mbf_msgs::ExePathResult result;
118 mbf_msgs::ExePathFeedback feedback;
121 bool controller_active =
true;
124 const mbf_msgs::ExePathGoal &goal = *(goal_handle.
getGoal().get());
126 const std::vector<geometry_msgs::PoseStamped> &plan = goal.path.poses;
129 fillExePathResult(mbf_msgs::ExePathResult::INVALID_PATH,
"Controller started with an empty plan!", result);
130 goal_handle.
setAborted(result, result.message);
132 controller_active =
false;
137 <<
name_ <<
"\" with plan:" << std::endl
138 <<
"frame: \"" << goal.path.header.frame_id <<
"\" " << std::endl
139 <<
"stamp: " << goal.path.header.stamp << std::endl
140 <<
"poses: " << goal.path.poses.size() << std::endl
141 <<
"goal: (" <<
goal_pose_.pose.position.x <<
", " 148 geometry_msgs::PoseStamped oscillation_pose;
151 bool first_cycle =
true;
153 while (controller_active &&
ros::ok())
159 controller_active =
false;
160 fillExePathResult(mbf_msgs::ExePathResult::TF_ERROR,
"Could not get the robot pose!", result);
162 goal_handle.
setAborted(result, result.message);
175 state_moving_input = execution.
getState();
177 switch (state_moving_input)
186 controller_active =
false;
191 fillExePathResult(mbf_msgs::ExePathResult::CANCELED,
"Controller canceled", result);
193 controller_active =
false;
217 controller_active =
false;
219 goal_handle.
setAborted(result, result.message);
224 controller_active =
false;
226 goal_handle.
setAborted(result, result.message);
231 controller_active =
false;
232 fillExePathResult(mbf_msgs::ExePathResult::INVALID_PATH,
"Controller started without a path", result);
233 goal_handle.
setAborted(result, result.message);
238 controller_active =
false;
239 fillExePathResult(mbf_msgs::ExePathResult::INVALID_PATH,
"Controller started with an empty plan", result);
240 goal_handle.
setAborted(result, result.message);
245 controller_active =
false;
246 fillExePathResult(mbf_msgs::ExePathResult::INVALID_PATH,
"Controller started with an invalid plan", result);
247 goal_handle.
setAborted(result, result.message);
257 if (!oscillation_timeout.
isZero())
265 else if (last_oscillation_reset + oscillation_timeout <
ros::Time::now())
270 controller_active =
false;
271 fillExePathResult(mbf_msgs::ExePathResult::OSCILLATION,
"Oscillation detected!", result);
272 goal_handle.
setAborted(result, result.message);
281 controller_active =
false;
282 fillExePathResult(mbf_msgs::ExePathResult::SUCCESS,
"Controller succeeded; arrived to goal!", result);
288 controller_active =
false;
289 fillExePathResult(mbf_msgs::ExePathResult::INTERNAL_ERROR,
"Internal error: Unknown error thrown by the plugin!", result);
290 goal_handle.
setAborted(result, result.message);
294 std::stringstream ss;
295 ss <<
"Internal error: Unknown state in a move base flex controller execution with the number: " 296 <<
static_cast<int>(state_moving_input);
299 goal_handle.
setAborted(result, result.message);
300 controller_active =
false;
304 if (controller_active)
315 if (!controller_active)
328 uint32_t outcome,
const std::string &message,
329 const geometry_msgs::TwistStamped& current_twist)
331 mbf_msgs::ExePathFeedback feedback;
332 feedback.outcome = outcome;
333 feedback.message = message;
335 feedback.last_cmd_vel = current_twist;
336 if (feedback.last_cmd_vel.header.stamp.isZero())
346 uint32_t outcome,
const std::string &message,
347 mbf_msgs::ExePathResult &result)
349 result.outcome = outcome;
350 result.message = message;
const RobotInformation & robot_info_
void publishFeedback(const Feedback &feedback)
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)
boost::mutex slot_map_mtx_
#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.
boost::shared_ptr< const Goal > getGoal() const
The controller has been started without a plan.
std::string getMessage()
Gets the current plugin execution message.
The AbstractControllerExecution class loads and binds the controller plugin. It contains a thread run...
void setCanceled(const Result &result=Result(), const std::string &text=std::string(""))
geometry_msgs::PoseStamped goal_pose_
Current goal pose.
Exceeded the patience time without a valid command.
void waitForStateUpdate(boost::chrono::microseconds const &duration)
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
#define ROS_WARN_STREAM_THROTTLE_NAMED(period, name, args)
const std::string & name_
#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
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 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)
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
ControllerState getState()
Return the current state of the controller execution. Thread communication safe.
ControllerAction(const std::string &name, const RobotInformation &robot_info)
#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.
virtual void start(GoalHandle &goal_handle, typename Execution::Ptr execution_ptr)
std::map< uint8_t, ConcurrencySlot > concurrency_slots_
uint32_t getOutcome()
Gets the current plugin execution outcome.
Controller has been started.
actionlib_msgs::GoalStatus getGoalStatus() const
#define ROS_WARN_STREAM_NAMED(name, args)
void setNewPlan(const std::vector< geometry_msgs::PoseStamped > &plan)
Sets a new plan to the controller execution.
The controller has been canceled.