abstract_controller_execution.h
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  * abstract_controller_execution.h
34  *
35  * authors:
36  * Sebastian Pütz <spuetz@uni-osnabrueck.de>
37  * Jorge Santos Simón <santos@magazino.eu>
38  *
39  */
40 
41 #ifndef MBF_ABSTRACT_NAV__ABSTRACT_CONTROLLER_EXECUTION_H_
42 #define MBF_ABSTRACT_NAV__ABSTRACT_CONTROLLER_EXECUTION_H_
43 
44 #include <map>
45 #include <string>
46 #include <vector>
47 
48 #include <geometry_msgs/PoseStamped.h>
49 #include <geometry_msgs/Twist.h>
50 
53 #include <mbf_utility/types.h>
54 
55 #include "mbf_abstract_nav/MoveBaseFlexConfig.h"
57 
59 {
60 
76  {
77  public:
78 
79  static const double DEFAULT_CONTROLLER_FREQUENCY;
80 
82 
90  const std::string &name,
91  const mbf_abstract_core::AbstractController::Ptr &controller_ptr,
92  const ros::Publisher &vel_pub,
93  const ros::Publisher &goal_pub,
94  const TFPtr &tf_listener_ptr,
95  const MoveBaseFlexConfig &config);
96 
101 
106  virtual bool start();
107 
115  void setNewPlan(
116  const std::vector<geometry_msgs::PoseStamped> &plan,
117  bool tolerance_from_action = false,
118  double action_dist_tolerance = 1.0,
119  double action_angle_tolerance = 3.1415);
120 
129  virtual bool cancel();
130 
135  {
150  };
151 
156  ControllerState getState() const;
157 
163 
170  geometry_msgs::TwistStamped getVelocityCmd() const;
171 
176  bool isPatienceExceeded() const;
177 
183  bool setControllerFrequency(double frequency);
184 
190  void reconfigure(const MoveBaseFlexConfig &config);
191 
196  bool isMoving() const;
197 
198  protected:
199 
210  virtual uint32_t computeVelocityCmd(const geometry_msgs::PoseStamped &pose,
211  const geometry_msgs::TwistStamped &velocity,
212  geometry_msgs::TwistStamped &vel_cmd, std::string &message);
213 
218  void setVelocityCmd(const geometry_msgs::TwistStamped &vel_cmd_stamped);
219 
221  std::string plugin_name_;
222 
225 
228 
231 
234 
237 
240 
243 
245  std::string robot_frame_;
246 
248  std::string global_frame_;
249 
253  virtual void run();
254 
262  virtual bool safetyCheck() { return true; };
263 
264  private:
265 
266 
270  void publishZeroVelocity();
271 
276  bool reachedGoalCheck();
277 
282  bool computeRobotPose();
283 
288  void setState(ControllerState state);
289 
291  mutable boost::mutex state_mtx_;
292 
294  mutable boost::mutex plan_mtx_;
295 
297  mutable boost::mutex vel_cmd_mtx_;
298 
300  mutable boost::mutex lct_mtx_;
301 
303  bool new_plan_;
304 
309  bool hasNewPlan();
310 
315  std::vector<geometry_msgs::PoseStamped> getNewPlan();
316 
318  geometry_msgs::TwistStamped vel_cmd_stamped_;
319 
321  std::vector<geometry_msgs::PoseStamped> plan_;
322 
325 
328 
331 
334 
336  double tf_timeout_;
337 
339  boost::mutex configuration_mutex_;
340 
342  bool moving_;
343 
346 
349 
352 
355 
358 
360  geometry_msgs::PoseStamped robot_pose_;
361 
364 
367 
370  };
371 
372 } /* namespace mbf_abstract_nav */
373 
374 #endif /* MBF_ABSTRACT_NAV__ABSTRACT_CONTROLLER_EXECUTION_H_ */
mbf_abstract_nav::AbstractControllerExecution::controller_
mbf_abstract_core::AbstractController::Ptr controller_
the local planer to calculate the velocity command
Definition: abstract_controller_execution.h:224
mbf_abstract_nav::AbstractControllerExecution::getVelocityCmd
geometry_msgs::TwistStamped getVelocityCmd() const
Returns the last velocity command calculated by the plugin. Set by setVelocityCmd method....
Definition: src/abstract_controller_execution.cpp:203
mbf_abstract_nav::AbstractControllerExecution::DEFAULT_CONTROLLER_FREQUENCY
static const double DEFAULT_CONTROLLER_FREQUENCY
Definition: abstract_controller_execution.h:79
mbf_abstract_nav::AbstractControllerExecution::tolerance_from_action_
bool tolerance_from_action_
whether check for action specific tolerance
Definition: abstract_controller_execution.h:363
mbf_abstract_nav::AbstractControllerExecution::MAX_RETRIES
@ MAX_RETRIES
Exceeded the maximum number of retries without a valid command.
Definition: abstract_controller_execution.h:140
mbf_abstract_nav::AbstractControllerExecution::last_valid_cmd_time_
ros::Time last_valid_cmd_time_
The time the controller responded with a success output (output < 10).
Definition: abstract_controller_execution.h:236
mbf_abstract_nav::AbstractControllerExecution::getNewPlan
std::vector< geometry_msgs::PoseStamped > getNewPlan()
Gets the new available plan. This method is thread safe.
Definition: src/abstract_controller_execution.cpp:160
ros::Publisher
mbf_abstract_nav::AbstractControllerExecution::ARRIVED_GOAL
@ ARRIVED_GOAL
The robot arrived the goal.
Definition: abstract_controller_execution.h:146
mbf_abstract_nav::AbstractControllerExecution::force_stop_at_goal_
bool force_stop_at_goal_
whether move base flex should force the robot to stop once the goal is reached.
Definition: abstract_controller_execution.h:348
mbf_abstract_nav::AbstractControllerExecution::tf_timeout_
double tf_timeout_
time before a timeout used for tf requests
Definition: abstract_controller_execution.h:336
mbf_abstract_nav::AbstractControllerExecution::lct_mtx_
boost::mutex lct_mtx_
mutex to handle safe thread communication for the last plugin call time
Definition: abstract_controller_execution.h:300
boost::shared_ptr
mbf_abstract_nav::AbstractControllerExecution::plan_mtx_
boost::mutex plan_mtx_
mutex to handle safe thread communication for the current plan
Definition: abstract_controller_execution.h:294
mbf_abstract_nav::AbstractControllerExecution::getState
ControllerState getState() const
Return the current state of the controller execution. Thread communication safe.
Definition: src/abstract_controller_execution.cpp:126
mbf_abstract_nav::AbstractControllerExecution::PLANNING
@ PLANNING
Executing the plugin.
Definition: abstract_controller_execution.h:138
mbf_abstract_nav::AbstractControllerExecution::current_goal_pub_
ros::Publisher current_goal_pub_
publisher for the current goal
Definition: abstract_controller_execution.h:330
mbf_abstract_nav::AbstractControllerExecution::vel_cmd_mtx_
boost::mutex vel_cmd_mtx_
mutex to handle safe thread communication for the current velocity command
Definition: abstract_controller_execution.h:297
mbf_abstract_nav::AbstractControllerExecution::INVALID_PLAN
@ INVALID_PLAN
Received an invalid plan that the controller plugin rejected.
Definition: abstract_controller_execution.h:143
mbf_abstract_nav::AbstractControllerExecution::ControllerState
ControllerState
Internal states.
Definition: abstract_controller_execution.h:134
mbf_abstract_nav::AbstractControllerExecution::angle_tolerance_
double angle_tolerance_
angle tolerance to the given goal pose
Definition: abstract_controller_execution.h:357
mbf_abstract_nav::AbstractControllerExecution::getLastPluginCallTime
ros::Time getLastPluginCallTime() const
Returns the time of the last plugin call.
Definition: src/abstract_controller_execution.cpp:209
mbf_abstract_nav::AbstractControllerExecution::robot_pose_
geometry_msgs::PoseStamped robot_pose_
current robot pose;
Definition: abstract_controller_execution.h:360
mbf_abstract_nav::AbstractControllerExecution::configuration_mutex_
boost::mutex configuration_mutex_
dynamic reconfigure config mutex, thread safe param reading and writing
Definition: abstract_controller_execution.h:339
mbf_abstract_nav::AbstractControllerExecution::hasNewPlan
bool hasNewPlan()
Returns true if a new plan is available, false otherwise! A new plan is set by another thread!
Definition: src/abstract_controller_execution.cpp:153
mbf_abstract_nav::AbstractControllerExecution::action_dist_tolerance_
double action_dist_tolerance_
replaces parameter dist_tolerance_ for the action
Definition: abstract_controller_execution.h:366
mbf_abstract_nav::AbstractControllerExecution::robot_frame_
std::string robot_frame_
the frame of the robot, which will be used to determine its position.
Definition: abstract_controller_execution.h:245
mbf_abstract_nav::AbstractControllerExecution::mbf_tolerance_check_
bool mbf_tolerance_check_
whether move base flex should check for the goal tolerance or not.
Definition: abstract_controller_execution.h:345
mbf_abstract_nav
Definition: abstract_controller_execution.h:58
mbf_abstract_nav::AbstractControllerExecution::NO_PLAN
@ NO_PLAN
The controller has been started without a plan.
Definition: abstract_controller_execution.h:139
mbf_abstract_nav::AbstractControllerExecution::plan_
std::vector< geometry_msgs::PoseStamped > plan_
the last set plan which is currently processed by the controller
Definition: abstract_controller_execution.h:321
mbf_abstract_nav::AbstractControllerExecution::patience_
ros::Duration patience_
The time / duration of patience, before changing the state.
Definition: abstract_controller_execution.h:242
mbf_abstract_nav::AbstractControllerExecution::state_
AbstractControllerExecution::ControllerState state_
the current controller state
Definition: abstract_controller_execution.h:333
mbf_abstract_nav::AbstractControllerExecution::publishZeroVelocity
void publishZeroVelocity()
Publishes a velocity command with zero values to stop the robot.
Definition: src/abstract_controller_execution.cpp:461
mbf_abstract_nav::AbstractControllerExecution::Ptr
boost::shared_ptr< AbstractControllerExecution > Ptr
Definition: abstract_controller_execution.h:81
mbf_abstract_nav::AbstractControllerExecution::reachedGoalCheck
bool reachedGoalCheck()
Checks whether the goal has been reached in the range of tolerance or not.
Definition: src/abstract_controller_execution.cpp:239
mbf_abstract_nav::AbstractControllerExecution::computeVelocityCmd
virtual uint32_t computeVelocityCmd(const geometry_msgs::PoseStamped &pose, const geometry_msgs::TwistStamped &velocity, geometry_msgs::TwistStamped &vel_cmd, std::string &message)
Request plugin for a new velocity command, given the current position, orientation,...
Definition: src/abstract_controller_execution.cpp:183
mbf_abstract_nav::AbstractControllerExecution::vel_pub_
ros::Publisher vel_pub_
publisher for the current velocity command
Definition: abstract_controller_execution.h:327
mbf_abstract_nav::AbstractControllerExecution::GOT_LOCAL_CMD
@ GOT_LOCAL_CMD
Got a valid velocity command from the plugin.
Definition: abstract_controller_execution.h:145
mbf_abstract_nav::AbstractControllerExecution::INITIALIZED
@ INITIALIZED
Controller has been initialized successfully.
Definition: abstract_controller_execution.h:136
mbf_abstract_nav::AbstractControllerExecution::moving_
bool moving_
main controller loop variable, true if the controller is running, false otherwise
Definition: abstract_controller_execution.h:342
mbf_abstract_nav::AbstractControllerExecution::plugin_name_
std::string plugin_name_
the name of the loaded plugin
Definition: abstract_controller_execution.h:221
mbf_abstract_nav::AbstractControllerExecution::computeRobotPose
bool computeRobotPose()
Computes the robot pose;.
Definition: src/abstract_controller_execution.cpp:168
mbf_abstract_nav::AbstractControllerExecution::INTERNAL_ERROR
@ INTERNAL_ERROR
An internal error occurred.
Definition: abstract_controller_execution.h:149
mbf_abstract_nav::AbstractControllerExecution::setControllerFrequency
bool setControllerFrequency(double frequency)
Sets the controller frequency.
Definition: src/abstract_controller_execution.cpp:83
mbf_abstract_nav::AbstractControllerExecution::EMPTY_PLAN
@ EMPTY_PLAN
Received an empty plan.
Definition: abstract_controller_execution.h:142
mbf_abstract_nav::AbstractControllerExecution::setState
void setState(ControllerState state)
Sets the controller state. This method makes the communication of the state thread safe.
Definition: src/abstract_controller_execution.cpp:120
mbf_abstract_nav::AbstractControllerExecution::cancel
virtual bool cancel()
Cancel the controller execution. Normally called upon aborting the navigation. This calls the cancel ...
Definition: src/abstract_controller_execution.cpp:255
mbf_abstract_nav::AbstractControllerExecution::start
virtual bool start()
Starts the controller, a valid plan should be given in advance.
Definition: src/abstract_controller_execution.cpp:108
mbf_abstract_nav::AbstractControllerExecution::~AbstractControllerExecution
virtual ~AbstractControllerExecution()
Destructor.
Definition: src/abstract_controller_execution.cpp:79
mbf_abstract_nav::AbstractControllerExecution::force_stop_on_cancel_
bool force_stop_on_cancel_
whether move base flex should force the robot to stop on canceling navigation.
Definition: abstract_controller_execution.h:351
abstract_controller.h
mbf_abstract_nav::AbstractControllerExecution::last_call_time_
ros::Time last_call_time_
The current cycle start time of the last cycle run. Will by updated each cycle.
Definition: abstract_controller_execution.h:230
mbf_abstract_nav::AbstractControllerExecution::global_frame_
std::string global_frame_
the global frame the robot is controlling in.
Definition: abstract_controller_execution.h:248
ros::Time
mbf_abstract_nav::AbstractControllerExecution::setVelocityCmd
void setVelocityCmd(const geometry_msgs::TwistStamped &vel_cmd_stamped)
Sets the velocity command, to make it available for another thread.
Definition: src/abstract_controller_execution.cpp:192
mbf_abstract_nav::AbstractControllerExecution::max_retries_
int max_retries_
The maximum number of retries.
Definition: abstract_controller_execution.h:239
mbf_abstract_nav::AbstractControllerExecution::AbstractControllerExecution
AbstractControllerExecution(const std::string &name, const mbf_abstract_core::AbstractController::Ptr &controller_ptr, const ros::Publisher &vel_pub, const ros::Publisher &goal_pub, const TFPtr &tf_listener_ptr, const MoveBaseFlexConfig &config)
Constructor.
Definition: src/abstract_controller_execution.cpp:50
mbf_abstract_nav::AbstractControllerExecution::start_time_
ros::Time start_time_
The time the controller has been started.
Definition: abstract_controller_execution.h:233
mbf_abstract_nav::AbstractControllerExecution::NO_LOCAL_CMD
@ NO_LOCAL_CMD
Received no velocity command by the plugin, in the current cycle.
Definition: abstract_controller_execution.h:144
mbf_abstract_nav::AbstractControllerExecution::STOPPED
@ STOPPED
The controller has been stopped!
Definition: abstract_controller_execution.h:148
mbf_abstract_nav::AbstractControllerExecution::run
virtual void run()
The main run method, a thread will execute this method. It contains the main controller execution loo...
Definition: src/abstract_controller_execution.cpp:280
mbf_abstract_nav::AbstractControllerExecution::CANCELED
@ CANCELED
The controller has been canceled.
Definition: abstract_controller_execution.h:147
mbf_abstract_nav::AbstractControllerExecution::vel_cmd_stamped_
geometry_msgs::TwistStamped vel_cmd_stamped_
the last calculated velocity command
Definition: abstract_controller_execution.h:318
mbf_abstract_nav::AbstractControllerExecution::loop_rate_
ros::Rate loop_rate_
the loop_rate which corresponds with the controller frequency.
Definition: abstract_controller_execution.h:324
mbf_abstract_nav::AbstractControllerExecution::STARTED
@ STARTED
Controller has been started.
Definition: abstract_controller_execution.h:137
abstract_execution_base.h
mbf_abstract_nav::AbstractControllerExecution::tf_listener_ptr
const TFPtr & tf_listener_ptr
shared pointer to the shared tf listener
Definition: abstract_controller_execution.h:227
ros::Rate
mbf_abstract_nav::AbstractControllerExecution::dist_tolerance_
double dist_tolerance_
distance tolerance to the given goal pose
Definition: abstract_controller_execution.h:354
mbf_abstract_nav::AbstractExecutionBase
Base class for running concurrent navigation tasks.
Definition: abstract_execution_base.h:57
mbf_abstract_nav::AbstractControllerExecution::new_plan_
bool new_plan_
true, if a new plan is available. See hasNewPlan()!
Definition: abstract_controller_execution.h:303
mbf_abstract_nav::AbstractControllerExecution::safetyCheck
virtual bool safetyCheck()
Check if its safe to drive. This method gets called at every controller cycle, stopping the robot if ...
Definition: abstract_controller_execution.h:262
mbf_abstract_nav::AbstractControllerExecution::reconfigure
void reconfigure(const MoveBaseFlexConfig &config)
Is called by the server thread to reconfigure the controller execution, if a user uses dynamic reconf...
Definition: src/abstract_controller_execution.cpp:95
types.h
mbf_abstract_nav::AbstractControllerExecution::setNewPlan
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.
Definition: src/abstract_controller_execution.cpp:132
mbf_abstract_nav::AbstractControllerExecution::state_mtx_
boost::mutex state_mtx_
mutex to handle safe thread communication for the current value of the state
Definition: abstract_controller_execution.h:291
mbf_abstract_nav::AbstractControllerExecution::PAT_EXCEEDED
@ PAT_EXCEEDED
Exceeded the patience time without a valid command.
Definition: abstract_controller_execution.h:141
mbf_abstract_nav::AbstractControllerExecution
The AbstractControllerExecution class loads and binds the controller plugin. It contains a thread run...
Definition: abstract_controller_execution.h:75
navigation_utility.h
ros::Duration
mbf_abstract_nav::AbstractControllerExecution::action_angle_tolerance_
double action_angle_tolerance_
replaces parameter angle_tolerance_ for the action
Definition: abstract_controller_execution.h:369
mbf_abstract_nav::AbstractControllerExecution::isMoving
bool isMoving() const
Returns whether the robot should normally move or not. True if the controller seems to work properly.
Definition: src/abstract_controller_execution.cpp:234
mbf_abstract_nav::AbstractControllerExecution::isPatienceExceeded
bool isPatienceExceeded() const
Checks whether the patience duration time has been exceeded, ot not.
Definition: src/abstract_controller_execution.cpp:215


mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Wed Mar 2 2022 00:33:47