Public Types | Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
mbf_mesh_nav::MeshControllerExecution Class Reference

The MeshControllerExecution binds a mesh to the AbstractControllerExecution and uses the mbf_mesh_core/MeshController class as base plugin interface. More...

#include <mesh_controller_execution.h>

Inheritance diagram for mbf_mesh_nav::MeshControllerExecution:
Inheritance graph
[legend]

Public Types

typedef boost::shared_ptr< mesh_map::MeshMapMeshPtr
 
- Public Types inherited from mbf_abstract_nav::AbstractControllerExecution
enum  ControllerState
 
typedef boost::shared_ptr< AbstractControllerExecutionPtr
 

Public Member Functions

 MeshControllerExecution (const std::string name, const mbf_mesh_core::MeshController::Ptr &controller_ptr, const ros::Publisher &vel_pub, const ros::Publisher &goal_pub, const TFPtr &tf_listener_ptr, const MeshPtr &mesh_ptr, const MoveBaseFlexConfig &config)
 Constructor. More...
 
virtual ~MeshControllerExecution ()
 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 () const
 
ControllerState getState () const
 
geometry_msgs::TwistStamped getVelocityCmd () const
 
bool isMoving () const
 
bool isPatienceExceeded () const
 
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 (const std::string &name)
 
const std::string & getMessage () const
 
const std::string & getName () const
 
uint32_t getOutcome () const
 
void join ()
 
virtual void postRun ()
 
virtual void preRun ()
 
virtual void reconfigure (MoveBaseFlexConfig &_cfg)
 
virtual void stop ()
 
boost::cv_status waitForStateUpdate (boost::chrono::microseconds const &duration)
 
virtual ~AbstractExecutionBase ()
 

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 mesh before calling the planner. More...
 
- Protected Member Functions inherited from mbf_abstract_nav::AbstractControllerExecution
virtual void run ()
 
virtual bool safetyCheck ()
 
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...
 
bool lock_mesh_
 Whether to lock mesh before calling the controller. More...
 
const MeshPtrmesh_ptr_
 mesh for 3d navigation planning 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
 
- 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_
 
std::string global_frame_
 
ros::Time last_call_time_
 
ros::Time last_valid_cmd_time_
 
int max_retries_
 
ros::Duration patience_
 
std::string plugin_name_
 
std::string robot_frame_
 
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 MeshControllerExecution binds a mesh to the AbstractControllerExecution and uses the mbf_mesh_core/MeshController class as base plugin interface.

Definition at line 55 of file mesh_controller_execution.h.

Member Typedef Documentation

◆ MeshPtr

Definition at line 58 of file mesh_controller_execution.h.

Constructor & Destructor Documentation

◆ MeshControllerExecution()

mbf_mesh_nav::MeshControllerExecution::MeshControllerExecution ( const std::string  name,
const mbf_mesh_core::MeshController::Ptr controller_ptr,
const ros::Publisher vel_pub,
const ros::Publisher goal_pub,
const TFPtr tf_listener_ptr,
const MeshPtr mesh_ptr,
const MoveBaseFlexConfig &  config 
)

Constructor.

Parameters
nameThe user defined name of the corresponding plugin
controller_ptrThe shared pointer to the plugin object
vel_pubThe velocity publisher for the controller execution
goal_pubThe current goal publisher fir the controller execution
tf_listener_ptrA shared pointer to the transform listener
mesh_ptrA pointer to the mesh map object
configThe current config object
setup_fnA setup function called before execution
cleanup_fnA cleanup function called after execution

Definition at line 41 of file mesh_controller_execution.cpp.

◆ ~MeshControllerExecution()

mbf_mesh_nav::MeshControllerExecution::~MeshControllerExecution ( )
virtual

Destructor.

Definition at line 53 of file mesh_controller_execution.cpp.

Member Function Documentation

◆ computeVelocityCmd()

uint32_t mbf_mesh_nav::MeshControllerExecution::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 mesh before calling the planner.

Parameters
robot_poseThe current pose of the robot.
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 in the ExePath action result and plugin's header.

Reimplemented from mbf_abstract_nav::AbstractControllerExecution.

Definition at line 70 of file mesh_controller_execution.cpp.

◆ toAbstract()

mbf_abstract_nav::MoveBaseFlexConfig mbf_mesh_nav::MeshControllerExecution::toAbstract ( const MoveBaseFlexConfig &  config)
private

Definition at line 57 of file mesh_controller_execution.cpp.

Member Data Documentation

◆ controller_name_

std::string mbf_mesh_nav::MeshControllerExecution::controller_name_
private

name of the controller plugin assigned by the class loader

Definition at line 110 of file mesh_controller_execution.h.

◆ lock_mesh_

bool mbf_mesh_nav::MeshControllerExecution::lock_mesh_
private

Whether to lock mesh before calling the controller.

Definition at line 107 of file mesh_controller_execution.h.

◆ mesh_ptr_

const MeshPtr& mbf_mesh_nav::MeshControllerExecution::mesh_ptr_
private

mesh for 3d navigation planning

Definition at line 104 of file mesh_controller_execution.h.


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


mbf_mesh_nav
Author(s): Sebastian Pütz
autogenerated on Thu Jan 25 2024 03:42:57