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>
|
| | 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...
|
| |
| | 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 () |
| |
| | 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 () |
| |
|
| 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...
|
| |
| virtual void | run () |
| |
| virtual bool | safetyCheck () |
| |
| void | setVelocityCmd (const geometry_msgs::TwistStamped &vel_cmd_stamped) |
| |
|
| mbf_abstract_nav::MoveBaseFlexConfig | toAbstract (const MoveBaseFlexConfig &config) |
| |
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.
◆ MeshPtr
◆ MeshControllerExecution()
Constructor.
- Parameters
-
| name | The user defined name of the corresponding plugin |
| controller_ptr | The shared pointer to the plugin object |
| vel_pub | The velocity publisher for the controller execution |
| goal_pub | The current goal publisher fir the controller execution |
| tf_listener_ptr | A shared pointer to the transform listener |
| mesh_ptr | A pointer to the mesh map object |
| config | The current config object |
| setup_fn | A setup function called before execution |
| cleanup_fn | A cleanup function called after execution |
Definition at line 41 of file mesh_controller_execution.cpp.
◆ ~MeshControllerExecution()
| mbf_mesh_nav::MeshControllerExecution::~MeshControllerExecution |
( |
| ) |
|
|
virtual |
◆ 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_pose | The current pose of the robot. |
| 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 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 |
◆ controller_name_
| std::string mbf_mesh_nav::MeshControllerExecution::controller_name_ |
|
private |
◆ lock_mesh_
| bool mbf_mesh_nav::MeshControllerExecution::lock_mesh_ |
|
private |
◆ mesh_ptr_
| const MeshPtr& mbf_mesh_nav::MeshControllerExecution::mesh_ptr_ |
|
private |
The documentation for this class was generated from the following files: