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 <stdint.h>
46 #include <string>
47 #include <vector>
48 
49 #include <tf/transform_listener.h>
50 #include <geometry_msgs/PoseStamped.h>
51 #include <geometry_msgs/Twist.h>
52 
55 #include <mbf_utility/types.h>
56 
57 #include "mbf_abstract_nav/MoveBaseFlexConfig.h"
59 
60 namespace mbf_abstract_nav
61 {
77  {
78  public:
79 
80  static const double DEFAULT_CONTROLLER_FREQUENCY;
81 
83 
91  const std::string name,
92  const mbf_abstract_core::AbstractController::Ptr& controller_ptr,
93  const ros::Publisher& vel_pub,
94  const ros::Publisher& goal_pub,
95  const TFPtr &tf_listener_ptr,
96  const MoveBaseFlexConfig &config,
97  boost::function<void()> setup_fn,
98  boost::function<void()> cleanup_fn);
99 
104 
109  virtual bool start();
110 
115  void setNewPlan(const std::vector<geometry_msgs::PoseStamped> &plan);
116 
122  virtual bool cancel();
123 
128  {
143  };
144 
150 
156 
163  geometry_msgs::TwistStamped getVelocityCmd();
164 
169  bool isPatienceExceeded();
170 
176  bool setControllerFrequency(double frequency);
177 
183  void reconfigure(const MoveBaseFlexConfig &config);
184 
189  bool isMoving();
190 
191  protected:
192 
203  virtual uint32_t computeVelocityCmd(const geometry_msgs::PoseStamped& pose,
204  const geometry_msgs::TwistStamped& velocity,
205  geometry_msgs::TwistStamped& vel_cmd, std::string& message);
206 
211  void setVelocityCmd(const geometry_msgs::TwistStamped &vel_cmd_stamped);
212 
214  std::string plugin_name_;
215 
218 
221 
224 
227 
230 
233 
237  virtual void run();
238 
239  private:
240 
241 
245  void publishZeroVelocity();
246 
251  bool reachedGoalCheck();
252 
257  bool computeRobotPose();
258 
263  void setState(ControllerState state);
264 
266  boost::mutex state_mtx_;
267 
269  boost::mutex plan_mtx_;
270 
272  boost::mutex vel_cmd_mtx_;
273 
275  boost::mutex lct_mtx_;
276 
278  bool new_plan_;
279 
284  bool hasNewPlan();
285 
290  std::vector<geometry_msgs::PoseStamped> getNewPlan();
291 
293  geometry_msgs::TwistStamped vel_cmd_stamped_;
294 
296  std::vector<geometry_msgs::PoseStamped> plan_;
297 
299  boost::chrono::microseconds calling_duration_;
300 
302  std::string robot_frame_;
303 
305  std::string global_frame_;
306 
309 
312 
315 
317  double tf_timeout_;
318 
320  boost::mutex configuration_mutex_;
321 
323  bool moving_;
324 
327 
330 
333 
335  geometry_msgs::PoseStamped robot_pose_;
336 
337  };
338 
339 } /* namespace mbf_abstract_nav */
340 
341 #endif /* MBF_ABSTRACT_NAV__ABSTRACT_CONTROLLER_EXECUTION_H_ */
boost::mutex plan_mtx_
mutex to handle safe thread communication for the current plan
bool new_plan_
true, if a new plan is available. See hasNewPlan()!
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, boost::function< void()> setup_fn, boost::function< void()> cleanup_fn)
Constructor.
std::string global_frame_
the global frame the robot is controlling in.
boost::chrono::microseconds calling_duration_
the duration which corresponds with the controller frequency.
ros::Duration patience_
The time / duration of patience, before changing the state.
boost::mutex configuration_mutex_
dynamic reconfigure config mutex, thread safe param reading and writing
boost::mutex vel_cmd_mtx_
mutex to handle safe thread communication for the current velocity command
Exceeded the maximum number of retries without a valid command.
Received no velocity command by the plugin, in the current cycle.
ros::Publisher current_goal_pub_
publisher for the current goal
bool hasNewPlan()
Returns true if a new plan is available, false otherwise! A new plan is set by another thread! ...
void setVelocityCmd(const geometry_msgs::TwistStamped &vel_cmd_stamped)
Sets the velocity command, to make it available for another thread.
double dist_tolerance_
distance tolerance to the given goal pose
The controller has been started without a plan.
void setState(ControllerState state)
Sets the controller state. This method makes the communication of the state thread safe...
The AbstractControllerExecution class loads and binds the controller plugin. It contains a thread run...
ros::Publisher vel_pub_
publisher for the current velocity command
const TFPtr & tf_listener_ptr
shared pointer to the shared tf listener
virtual bool cancel()
Cancel the planner execution. This calls the cancel method of the planner plugin. This could be usefu...
virtual void run()
The main run method, a thread will execute this method. It contains the main controller execution loo...
boost::shared_ptr< AbstractControllerExecution > Ptr
geometry_msgs::TwistStamped vel_cmd_stamped_
the last calculated velocity command
Exceeded the patience time without a valid command.
bool isMoving()
Returns whether the robot should normally move or not. True if the controller seems to work properly...
bool mbf_tolerance_check_
whether move base flex should check for the goal tolerance or not.
AbstractControllerExecution::ControllerState state_
the current controller state
bool moving_
main controller loop variable, true if the controller is running, false otherwise ...
std::string plugin_name_
the name of the loaded plugin
bool isPatienceExceeded()
Checks whether the patience duration time has been exceeded, ot not.
double angle_tolerance_
angle tolerance to the given goal pose
boost::mutex state_mtx_
mutex to handle safe thread communication for the current value of the state
ros::Time getLastPluginCallTime()
Returns the time of the last plugin call.
ros::Time start_time_
The time the controller has been started.
std::vector< geometry_msgs::PoseStamped > getNewPlan()
Gets the new available plan. This method is thread safe.
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, and velocity of the robot. We use this virtual method to give concrete implementations as move_base the chance to override it and do additional stuff, for example locking the costmap.
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...
bool reachedGoalCheck()
Checks whether the goal has been reached in the range of tolerance or not.
mbf_abstract_core::AbstractController::Ptr controller_
the local planer to calculate the velocity command
ControllerState getState()
Return the current state of the controller execution. Thread communication safe.
boost::mutex lct_mtx_
mutex to handle safe thread communication for the last plugin call time
geometry_msgs::PoseStamped robot_pose_
current robot pose;
std::string robot_frame_
the frame of the robot, which will be used to determine its position.
void reconfigure(const MoveBaseFlexConfig &config)
Is called by the server thread to reconfigure the controller execution, if a user uses dynamic reconf...
virtual bool start()
Starts the controller, a valid plan should be given in advance.
double tf_timeout_
time before a timeout used for tf requests
bool setControllerFrequency(double frequency)
Sets the controller frequency.
std::vector< geometry_msgs::PoseStamped > plan_
the last set plan which is currently processed by the controller
ros::Time last_call_time_
The current cycle start time of the last cycle run. Will by updated each cycle.
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