controller_action.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions
6  * are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above
12  * copyright notice, this list of conditions and the following
13  * disclaimer in the documentation and/or other materials provided
14  * with the distribution.
15  *
16  * 3. Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived
18  * from this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  * controller_action.cpp
34  *
35  * authors:
36  * Sebastian Pütz <spuetz@uni-osnabrueck.de>
37  * Jorge Santos Simón <santos@magazino.eu>
38  *
39  */
40 
42 
43 namespace mbf_abstract_nav{
44 
45 
47  const std::string &action_name,
48  const RobotInformation &robot_info)
49  : AbstractAction(action_name, robot_info, boost::bind(&mbf_abstract_nav::ControllerAction::run, this, _1, _2))
50 {
51 }
52 
54  GoalHandle &goal_handle,
55  typename AbstractControllerExecution::Ptr execution_ptr
56 )
57 {
58  if(goal_handle.getGoalStatus().status == actionlib_msgs::GoalStatus::RECALLING)
59  {
60  goal_handle.setCanceled();
61  return;
62  }
63 
64  uint8_t slot = goal_handle.getGoal()->concurrency_slot;
65 
66  bool update_plan = false;
67  slot_map_mtx_.lock();
68  std::map<uint8_t, ConcurrencySlot>::iterator slot_it = concurrency_slots_.find(slot);
69  if(slot_it != concurrency_slots_.end())
70  {
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())
74  {
75  update_plan = true;
76  // Goal requests to run the same controller on the same concurrency slot:
77  // we update the goal handle and pass the new plan to the execution without stopping it
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);
82  concurrency_slots_[slot].goal_handle.setCanceled(result, result.message);
83  concurrency_slots_[slot].goal_handle = goal_handle;
84  concurrency_slots_[slot].goal_handle.setAccepted();
85  }
86  }
87  slot_map_mtx_.unlock();
88  if(!update_plan)
89  {
90  // Otherwise run parent version of this method
91  AbstractAction::start(goal_handle, execution_ptr);
92  }
93 }
94 
96 {
97  goal_mtx_.lock();
98  // Note that we always use the goal handle stored on the concurrency slots map, as it can change when replanning
99  uint8_t slot = goal_handle.getGoal()->concurrency_slot;
100  goal_mtx_.unlock();
101 
102  ROS_DEBUG_STREAM_NAMED(name_, "Start action " << name_);
103 
104  // ensure we don't provide values from previous execution on case of error before filling both poses
105  goal_pose_ = geometry_msgs::PoseStamped();
106  robot_pose_ = geometry_msgs::PoseStamped();
107 
108  ros::NodeHandle private_nh("~");
109 
110  double oscillation_timeout_tmp;
111  private_nh.param("oscillation_timeout", oscillation_timeout_tmp, 0.0);
112  ros::Duration oscillation_timeout(oscillation_timeout_tmp);
113 
114  double oscillation_distance;
115  private_nh.param("oscillation_distance", oscillation_distance, 0.03);
116 
117  mbf_msgs::ExePathResult result;
118  mbf_msgs::ExePathFeedback feedback;
119 
120  typename AbstractControllerExecution::ControllerState state_moving_input;
121  bool controller_active = true;
122 
123  goal_mtx_.lock();
124  const mbf_msgs::ExePathGoal &goal = *(goal_handle.getGoal().get());
125 
126  const std::vector<geometry_msgs::PoseStamped> &plan = goal.path.poses;
127  if (plan.empty())
128  {
129  fillExePathResult(mbf_msgs::ExePathResult::INVALID_PATH, "Controller started with an empty plan!", result);
130  goal_handle.setAborted(result, result.message);
131  ROS_ERROR_STREAM_NAMED(name_, result.message << " Canceling the action call.");
132  controller_active = false;
133  }
134 
135  goal_pose_ = plan.back();
136  ROS_DEBUG_STREAM_NAMED(name_, "Called action \""
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 << ", "
142  << goal_pose_.pose.position.y << ", "
143  << goal_pose_.pose.position.z << ")");
144 
145  goal_mtx_.unlock();
146 
147 
148  geometry_msgs::PoseStamped oscillation_pose;
149  ros::Time last_oscillation_reset = ros::Time::now();
150 
151  bool first_cycle = true;
152 
153  while (controller_active && ros::ok())
154  {
155  // goal_handle could change between the loop cycles due to adapting the plan
156  // with a new goal received for the same concurrency slot
158  {
159  controller_active = false;
160  fillExePathResult(mbf_msgs::ExePathResult::TF_ERROR, "Could not get the robot pose!", result);
161  goal_mtx_.lock();
162  goal_handle.setAborted(result, result.message);
163  goal_mtx_.unlock();
164  ROS_ERROR_STREAM_NAMED(name_, result.message << " Canceling the action call.");
165  break;
166  }
167 
168  if (first_cycle)
169  {
170  // init oscillation pose
171  oscillation_pose = robot_pose_;
172  }
173 
174  goal_mtx_.lock();
175  state_moving_input = execution.getState();
176 
177  switch (state_moving_input)
178  {
180  execution.setNewPlan(plan);
181  execution.start();
182  break;
183 
185  ROS_WARN_STREAM_NAMED(name_, "The controller has been stopped!");
186  controller_active = false;
187  break;
188 
190  ROS_INFO_STREAM("Action \"exe_path\" canceled");
191  fillExePathResult(mbf_msgs::ExePathResult::CANCELED, "Controller canceled", result);
192  goal_handle.setCanceled(result, result.message);
193  controller_active = false;
194  break;
195 
197  ROS_DEBUG_STREAM_NAMED(name_, "The moving has been started!");
198  break;
199 
200  // in progress
202  if (execution.isPatienceExceeded())
203  {
204  ROS_DEBUG_STREAM_NAMED(name_, "The controller patience has been exceeded! Stopping controller...");
205  // TODO planner is stuck, but we don't have currently any way to cancel it!
206  // We will try to stop the thread, but does nothing with DWA or TR controllers
207  // Note that this is not the same situation as in case AbstractControllerExecution::PAT_EXCEEDED,
208  // as there is the controller itself reporting that it cannot find a valid command after trying
209  // for more than patience seconds. But after stopping controller execution, it should ideally
210  // report PAT_EXCEEDED as his state on next iteration.
211  execution.stop();
212  }
213  break;
214 
216  ROS_WARN_STREAM_NAMED(name_, "The controller has been aborted after it exceeded the maximum number of retries!");
217  controller_active = false;
218  fillExePathResult(execution.getOutcome(), execution.getMessage(), result);
219  goal_handle.setAborted(result, result.message);
220  break;
221 
223  ROS_WARN_STREAM_NAMED(name_, "The controller has been aborted after it exceeded the patience time");
224  controller_active = false;
225  fillExePathResult(mbf_msgs::ExePathResult::PAT_EXCEEDED, execution.getMessage(), result);
226  goal_handle.setAborted(result, result.message);
227  break;
228 
230  ROS_WARN_STREAM_NAMED(name_, "The controller has been started without a plan!");
231  controller_active = false;
232  fillExePathResult(mbf_msgs::ExePathResult::INVALID_PATH, "Controller started without a path", result);
233  goal_handle.setAborted(result, result.message);
234  break;
235 
237  ROS_WARN_STREAM_NAMED(name_, "The controller has received an empty plan");
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);
241  break;
242 
244  ROS_WARN_STREAM_NAMED(name_, "The controller has received an invalid plan");
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);
248  break;
249 
251  ROS_WARN_STREAM_THROTTLE_NAMED(3, name_, "No velocity command received from controller! "
252  << execution.getMessage());
253  publishExePathFeedback(goal_handle, execution.getOutcome(), execution.getMessage(), execution.getVelocityCmd());
254  break;
255 
257  if (!oscillation_timeout.isZero())
258  {
259  // check if oscillating
260  if (mbf_utility::distance(robot_pose_, oscillation_pose) >= oscillation_distance)
261  {
262  last_oscillation_reset = ros::Time::now();
263  oscillation_pose = robot_pose_;
264  }
265  else if (last_oscillation_reset + oscillation_timeout < ros::Time::now())
266  {
267  ROS_WARN_STREAM_NAMED(name_, "The controller is oscillating for "
268  << (ros::Time::now() - last_oscillation_reset).toSec() << "s");
269  execution.stop();
270  controller_active = false;
271  fillExePathResult(mbf_msgs::ExePathResult::OSCILLATION, "Oscillation detected!", result);
272  goal_handle.setAborted(result, result.message);
273  break;
274  }
275  }
276  publishExePathFeedback(goal_handle, execution.getOutcome(), execution.getMessage(), execution.getVelocityCmd());
277  break;
278 
280  ROS_DEBUG_STREAM_NAMED(name_, "Controller succeeded; arrived to goal");
281  controller_active = false;
282  fillExePathResult(mbf_msgs::ExePathResult::SUCCESS, "Controller succeeded; arrived to goal!", result);
283  goal_handle.setSucceeded(result, result.message);
284  break;
285 
287  ROS_FATAL_STREAM_NAMED(name_, "Internal error: Unknown error thrown by the plugin: " << execution.getMessage());
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);
291  break;
292 
293  default:
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);
297  fillExePathResult(mbf_msgs::ExePathResult::INTERNAL_ERROR, ss.str(), result);
298  ROS_FATAL_STREAM_NAMED(name_, result.message);
299  goal_handle.setAborted(result, result.message);
300  controller_active = false;
301  }
302  goal_mtx_.unlock();
303 
304  if (controller_active)
305  {
306  // try to sleep a bit
307  // normally this thread should be woken up from the controller execution thread
308  // in order to transfer the results to the controller
309  execution.waitForStateUpdate(boost::chrono::milliseconds(500));
310  }
311 
312  first_cycle = false;
313  } // while (controller_active && ros::ok())
314 
315  if (!controller_active)
316  {
317  ROS_DEBUG_STREAM_NAMED(name_, "\"" << name_ << "\" action ended properly.");
318  }
319  else
320  {
321  // normal on continuous replanning
322  ROS_DEBUG_STREAM_NAMED(name_, "\"" << name_ << "\" action has been stopped!");
323  }
324 }
325 
327  GoalHandle& goal_handle,
328  uint32_t outcome, const std::string &message,
329  const geometry_msgs::TwistStamped& current_twist)
330 {
331  mbf_msgs::ExePathFeedback feedback;
332  feedback.outcome = outcome;
333  feedback.message = message;
334 
335  feedback.last_cmd_vel = current_twist;
336  if (feedback.last_cmd_vel.header.stamp.isZero())
337  feedback.last_cmd_vel.header.stamp = ros::Time::now();
338 
339  feedback.current_pose = robot_pose_;
340  feedback.dist_to_goal = static_cast<float>(mbf_utility::distance(robot_pose_, goal_pose_));
341  feedback.angle_to_goal = static_cast<float>(mbf_utility::angle(robot_pose_, goal_pose_));
342  goal_handle.publishFeedback(feedback);
343 }
344 
346  uint32_t outcome, const std::string &message,
347  mbf_msgs::ExePathResult &result)
348 {
349  result.outcome = outcome;
350  result.message = message;
351  result.final_pose = robot_pose_;
352  result.dist_to_goal = static_cast<float>(mbf_utility::distance(robot_pose_, goal_pose_));
353  result.angle_to_goal = static_cast<float>(mbf_utility::angle(robot_pose_, goal_pose_));
354 }
355 
356 }
357 
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.
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)
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)
boost::shared_ptr< const Goal > getGoal() const
The controller has been started without a plan.
bool getRobotPose(geometry_msgs::PoseStamped &robot_pose) const
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)
#define ROS_FATAL_STREAM_NAMED(name, args)
bool isPatienceExceeded()
Checks whether the patience duration time has been exceeded, ot not.
bool param(const std::string &param_name, T &param_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...
ROSCPP_DECL bool ok()
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 &current_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
static Time now()
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)
uint32_t getOutcome()
Gets the current plugin execution outcome.
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.


mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Tue Jun 18 2019 19:34:34