The CostmapControllerExecution binds a local costmap to the AbstractControllerExecution and uses the nav_core/BaseLocalPlanner class as base plugin interface. This class makes move_base_flex compatible to the old move_base. More...
#include <costmap_controller_execution.h>

Public Types | |
| typedef boost::shared_ptr < costmap_2d::Costmap2DROS > | CostmapPtr |
Public Member Functions | |
| CostmapControllerExecution (const std::string name, const mbf_costmap_core::CostmapController::Ptr &controller_ptr, const ros::Publisher &vel_pub, const ros::Publisher &goal_pub, const TFPtr &tf_listener_ptr, CostmapPtr &costmap_ptr, const MoveBaseFlexConfig &config, boost::function< void()> setup_fn, boost::function< void()> cleanup_fn) | |
| Constructor. | |
| virtual | ~CostmapControllerExecution () |
| Destructor. | |
Protected Member Functions | |
| virtual uint32_t | computeVelocityCmd (const geometry_msgs::PoseStamped &robot_pose, const geometry_msgs::TwistStamped &robot_velocity, geometry_msgs::TwistStamped &vel_cmd, std::string &message) |
| Request plugin for a new velocity command. We override this method so we can lock the local costmap before calling the planner. | |
Private Member Functions | |
| mbf_abstract_nav::MoveBaseFlexConfig | toAbstract (const MoveBaseFlexConfig &config) |
Private Attributes | |
| std::string | controller_name_ |
| name of the controller plugin assigned by the class loader | |
| CostmapPtr & | costmap_ptr_ |
| costmap for 2d navigation planning | |
| bool | lock_costmap_ |
| Whether to lock costmap before calling the controller (see issue #4 for details) | |
The CostmapControllerExecution binds a local costmap to the AbstractControllerExecution and uses the nav_core/BaseLocalPlanner class as base plugin interface. This class makes move_base_flex compatible to the old move_base.
Definition at line 58 of file costmap_controller_execution.h.
| typedef boost::shared_ptr<costmap_2d::Costmap2DROS> mbf_costmap_nav::CostmapControllerExecution::CostmapPtr |
Definition at line 62 of file costmap_controller_execution.h.
| mbf_costmap_nav::CostmapControllerExecution::CostmapControllerExecution | ( | const std::string | name, |
| const mbf_costmap_core::CostmapController::Ptr & | controller_ptr, | ||
| const ros::Publisher & | vel_pub, | ||
| const ros::Publisher & | goal_pub, | ||
| const TFPtr & | tf_listener_ptr, | ||
| CostmapPtr & | costmap_ptr, | ||
| const MoveBaseFlexConfig & | config, | ||
| boost::function< void()> | setup_fn, | ||
| boost::function< void()> | cleanup_fn | ||
| ) |
Constructor.
| condition | Thread sleep condition variable, to wake up connected threads |
| tf_listener_ptr | Shared pointer to a common tf listener |
| costmap_ptr | Shared pointer to the costmap. |
Definition at line 45 of file costmap_controller_execution.cpp.
Destructor.
Definition at line 63 of file costmap_controller_execution.cpp.
| uint32_t mbf_costmap_nav::CostmapControllerExecution::computeVelocityCmd | ( | const geometry_msgs::PoseStamped & | robot_pose, |
| const geometry_msgs::TwistStamped & | robot_velocity, | ||
| geometry_msgs::TwistStamped & | vel_cmd, | ||
| std::string & | message | ||
| ) | [protected, virtual] |
Request plugin for a new velocity command. We override this method so we can lock the local costmap before calling the planner.
| pose | the current pose of the robot. |
| velocity | the current velocity of the robot. |
| cmd_vel | Will be filled with the velocity command to be passed to the robot base. |
| message | Optional more detailed outcome as a string. |
Reimplemented from mbf_abstract_nav::AbstractControllerExecution.
Definition at line 79 of file costmap_controller_execution.cpp.
| mbf_abstract_nav::MoveBaseFlexConfig mbf_costmap_nav::CostmapControllerExecution::toAbstract | ( | const MoveBaseFlexConfig & | config | ) | [private] |
Definition at line 67 of file costmap_controller_execution.cpp.
std::string mbf_costmap_nav::CostmapControllerExecution::controller_name_ [private] |
name of the controller plugin assigned by the class loader
Definition at line 114 of file costmap_controller_execution.h.
costmap for 2d navigation planning
Definition at line 108 of file costmap_controller_execution.h.
bool mbf_costmap_nav::CostmapControllerExecution::lock_costmap_ [private] |
Whether to lock costmap before calling the controller (see issue #4 for details)
Definition at line 111 of file costmap_controller_execution.h.