Public Types | Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
mbf_costmap_nav::CostmapControllerExecution Class Reference

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>

Inheritance diagram for mbf_costmap_nav::CostmapControllerExecution:
Inheritance graph
[legend]

Public Types

typedef boost::shared_ptr< costmap_2d::Costmap2DROSCostmapPtr
 
- Public Types inherited from mbf_abstract_nav::AbstractControllerExecution
enum  ControllerState
 
typedef boost::shared_ptr< AbstractControllerExecutionPtr
 

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. 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, 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 ()
 
- Public Member Functions inherited from mbf_abstract_nav::AbstractExecutionBase
 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)
 

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. More...
 
- Protected Member Functions inherited from mbf_abstract_nav::AbstractControllerExecution
virtual void run ()
 
void setVelocityCmd (const geometry_msgs::TwistStamped &vel_cmd_stamped)
 

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 More...
 
CostmapPtrcostmap_ptr_
 costmap for 2d navigation planning More...
 
bool lock_costmap_
 Whether to lock costmap before calling the controller (see issue #4 for details) More...
 

Additional Inherited Members

- Public Attributes inherited from mbf_abstract_nav::AbstractControllerExecution
 ARRIVED_GOAL
 
 CANCELED
 
 EMPTY_PLAN
 
 GOT_LOCAL_CMD
 
 INITIALIZED
 
 INTERNAL_ERROR
 
 INVALID_PLAN
 
 MAX_RETRIES
 
 NO_LOCAL_CMD
 
 NO_PLAN
 
 PAT_EXCEEDED
 
 PLANNING
 
 STARTED
 
 STOPPED
 
- Public Attributes inherited from mbf_abstract_nav::AbstractExecutionBase
boost::function< void()> cleanup_fn_
 
boost::function< void()> setup_fn_
 
- Static Public Attributes inherited from mbf_abstract_nav::AbstractControllerExecution
static const double DEFAULT_CONTROLLER_FREQUENCY
 
- Protected Attributes inherited from mbf_abstract_nav::AbstractControllerExecution
mbf_abstract_core::AbstractController::Ptr controller_
 
ros::Time last_call_time_
 
int max_retries_
 
ros::Duration patience_
 
std::string plugin_name_
 
ros::Time start_time_
 
const TFPtrtf_listener_ptr
 
- Protected Attributes inherited from mbf_abstract_nav::AbstractExecutionBase
bool cancel_
 
boost::condition_variable condition_
 
std::string message_
 
std::string name_
 
uint32_t outcome_
 
boost::thread thread_
 

Detailed Description

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.

Member Typedef Documentation

Definition at line 62 of file costmap_controller_execution.h.

Constructor & Destructor Documentation

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.

Parameters
conditionThread sleep condition variable, to wake up connected threads
tf_listener_ptrShared pointer to a common tf listener
costmap_ptrShared pointer to the costmap.

Definition at line 45 of file costmap_controller_execution.cpp.

mbf_costmap_nav::CostmapControllerExecution::~CostmapControllerExecution ( )
virtual

Destructor.

Definition at line 63 of file costmap_controller_execution.cpp.

Member Function Documentation

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
posethe current pose of the robot.
velocitythe current velocity of the robot.
cmd_velWill be filled with the velocity command to be passed to the robot base.
messageOptional 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

Definition at line 67 of file costmap_controller_execution.cpp.

Member Data Documentation

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.

CostmapPtr& mbf_costmap_nav::CostmapControllerExecution::costmap_ptr_
private

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.


The documentation for this class was generated from the following files:


mbf_costmap_nav
Author(s): Sebastian Pütz
autogenerated on Tue Jun 18 2019 19:34:40