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>
|
| 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. More...
|
|
virtual | ~CostmapControllerExecution () |
| Destructor. More...
|
|
| 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) |
|
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) |
|
virtual bool | start () |
|
virtual | ~AbstractControllerExecution () |
|
| AbstractExecutionBase (std::string name, boost::function< void()> setup_fn, boost::function< void()> cleanup_fn) |
|
std::string | getMessage () |
|
std::string | getName () |
|
uint32_t | getOutcome () |
|
void | join () |
|
virtual void | stop () |
|
void | waitForStateUpdate (boost::chrono::microseconds const &duration) |
|
|
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...
|
|
virtual void | run () |
|
void | setVelocityCmd (const geometry_msgs::TwistStamped &vel_cmd_stamped) |
|
|
mbf_abstract_nav::MoveBaseFlexConfig | toAbstract (const MoveBaseFlexConfig &config) |
|
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.
Constructor.
- Parameters
-
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.
mbf_costmap_nav::CostmapControllerExecution::~CostmapControllerExecution |
( |
| ) |
|
|
virtual |
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 |
|
) |
| |
|
protectedvirtual |
Request plugin for a new velocity command. We override this method so we can lock the local costmap before calling the planner.
- Parameters
-
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. |
- Returns
- Result code as described on ExePath action result and plugin's header.
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 |
std::string mbf_costmap_nav::CostmapControllerExecution::controller_name_ |
|
private |
CostmapPtr& mbf_costmap_nav::CostmapControllerExecution::costmap_ptr_ |
|
private |
bool mbf_costmap_nav::CostmapControllerExecution::lock_costmap_ |
|
private |
The documentation for this class was generated from the following files: