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 Member Functions | |
| CostmapControllerExecution (const std::string &controller_name, const mbf_costmap_core::CostmapController::Ptr &controller_ptr, const ros::Publisher &vel_pub, const ros::Publisher &goal_pub, const TFPtr &tf_listener_ptr, const CostmapWrapper::Ptr &costmap_ptr, const MoveBaseFlexConfig &config) | |
| Constructor.  More... | |
| virtual | ~CostmapControllerExecution () | 
| Destructor.  More... | |
|  Public Member Functions inherited from mbf_abstract_nav::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) | |
| virtual bool | cancel () | 
| ros::Time | getLastPluginCallTime () | 
| ControllerState | getState () | 
| geometry_msgs::TwistStamped | getVelocityCmd () | 
| bool | isMoving () | 
| bool | isPatienceExceeded () | 
| void | reconfigure (const MoveBaseFlexConfig &config) | 
| bool | setControllerFrequency (double frequency) | 
| 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) | 
| virtual bool | start () | 
| virtual | ~AbstractControllerExecution () | 
|  Public Member Functions inherited from mbf_abstract_nav::AbstractExecutionBase | |
| AbstractExecutionBase (std::string name) | |
| std::string | getMessage () | 
| std::string | getName () | 
| uint32_t | getOutcome () | 
| void | join () | 
| virtual void | stop () | 
| boost::cv_status | waitForStateUpdate (boost::chrono::microseconds const &duration) | 
| Private 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.  More... | |
| void | postRun () | 
| Implementation-specific cleanup function, called right after execution. This method overrides abstract execution empty implementation with underlying map-specific cleanup code.  More... | |
| void | preRun () | 
| Implementation-specific setup function, called right before execution. This method overrides abstract execution empty implementation with underlying map-specific setup code.  More... | |
| bool | safetyCheck () | 
| Implementation-specific safety check, called during execution to ensure it's safe to drive. This method overrides abstract execution empty implementation with underlying map-specific checks, more precisely if controller costmap is current.  More... | |
| mbf_abstract_nav::MoveBaseFlexConfig | toAbstract (const MoveBaseFlexConfig &config) | 
| Private Attributes | |
| std::string | controller_name_ | 
| name of the controller plugin assigned by the class loader  More... | |
| const CostmapWrapper::Ptr & | costmap_ptr_ | 
| Shared pointer to thr local costmap.  More... | |
| bool | lock_costmap_ | 
| Whether to lock costmap before calling the controller (see issue #4 for details)  More... | |
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 60 of file costmap_controller_execution.h.
| mbf_costmap_nav::CostmapControllerExecution::CostmapControllerExecution | ( | const std::string & | controller_name, | 
| const mbf_costmap_core::CostmapController::Ptr & | controller_ptr, | ||
| const ros::Publisher & | vel_pub, | ||
| const ros::Publisher & | goal_pub, | ||
| const TFPtr & | tf_listener_ptr, | ||
| const CostmapWrapper::Ptr & | costmap_ptr, | ||
| const MoveBaseFlexConfig & | config | ||
| ) | 
Constructor.
| controller_name | Name of the controller to use. | 
| controller_ptr | Shared pointer to the plugin to use. | 
| vel_pub | Velocity commands publisher. | 
| goal_pub | Goal pose publisher (just vor visualization). | 
| tf_listener_ptr | Shared pointer to a common tf listener. | 
| costmap_ptr | Shared pointer to the local costmap. | 
| config | Current server configuration (dynamic). | 
Definition at line 45 of file costmap_controller_execution.cpp.
| 
 | virtual | 
Destructor.
Definition at line 61 of file costmap_controller_execution.cpp.
| 
 | privatevirtual | 
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 77 of file costmap_controller_execution.cpp.
| 
 | inlineprivatevirtual | 
Implementation-specific cleanup function, called right after execution. This method overrides abstract execution empty implementation with underlying map-specific cleanup code.
Reimplemented from mbf_abstract_nav::AbstractExecutionBase.
Definition at line 103 of file costmap_controller_execution.h.
| 
 | inlineprivatevirtual | 
Implementation-specific setup function, called right before execution. This method overrides abstract execution empty implementation with underlying map-specific setup code.
Reimplemented from mbf_abstract_nav::AbstractExecutionBase.
Definition at line 94 of file costmap_controller_execution.h.
| 
 | privatevirtual | 
Implementation-specific safety check, called during execution to ensure it's safe to drive. This method overrides abstract execution empty implementation with underlying map-specific checks, more precisely if controller costmap is current.
Reimplemented from mbf_abstract_nav::AbstractControllerExecution.
Definition at line 92 of file costmap_controller_execution.cpp.
| 
 | private | 
Definition at line 65 of file costmap_controller_execution.cpp.
| 
 | private | 
name of the controller plugin assigned by the class loader
Definition at line 140 of file costmap_controller_execution.h.
| 
 | private | 
Shared pointer to thr local costmap.
Definition at line 134 of file costmap_controller_execution.h.
| 
 | private | 
Whether to lock costmap before calling the controller (see issue #4 for details)
Definition at line 137 of file costmap_controller_execution.h.