#include <abstract_controller.h>
Public Types | |
typedef boost::shared_ptr < ::mbf_abstract_core::AbstractController > | Ptr |
Public Member Functions | |
virtual bool | cancel ()=0 |
Requests the planner to cancel, e.g. if it takes too much time. | |
virtual uint32_t | computeVelocityCommands (const geometry_msgs::PoseStamped &pose, const geometry_msgs::TwistStamped &velocity, geometry_msgs::TwistStamped &cmd_vel, std::string &message)=0 |
Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base. | |
virtual bool | isGoalReached (double dist_tolerance, double angle_tolerance)=0 |
Check if the goal pose has been achieved by the local planner. | |
virtual bool | setPlan (const std::vector< geometry_msgs::PoseStamped > &plan)=0 |
Set the plan that the local planner is following. | |
virtual | ~AbstractController () |
Destructor. | |
Protected Member Functions | |
AbstractController () | |
Constructor. |
Definition at line 51 of file abstract_controller.h.
typedef boost::shared_ptr< ::mbf_abstract_core::AbstractController > mbf_abstract_core::AbstractController::Ptr |
Definition at line 55 of file abstract_controller.h.
virtual mbf_abstract_core::AbstractController::~AbstractController | ( | ) | [inline, virtual] |
Destructor.
Definition at line 60 of file abstract_controller.h.
mbf_abstract_core::AbstractController::AbstractController | ( | ) | [inline, protected] |
Constructor.
Definition at line 119 of file abstract_controller.h.
virtual bool mbf_abstract_core::AbstractController::cancel | ( | ) | [pure virtual] |
Requests the planner to cancel, e.g. if it takes too much time.
virtual uint32_t mbf_abstract_core::AbstractController::computeVelocityCommands | ( | const geometry_msgs::PoseStamped & | pose, |
const geometry_msgs::TwistStamped & | velocity, | ||
geometry_msgs::TwistStamped & | cmd_vel, | ||
std::string & | message | ||
) | [pure virtual] |
Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base.
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 |
virtual bool mbf_abstract_core::AbstractController::isGoalReached | ( | double | dist_tolerance, |
double | angle_tolerance | ||
) | [pure virtual] |
Check if the goal pose has been achieved by the local planner.
angle_tolerance | The angle tolerance in which the current pose will be partly accepted as reached goal |
dist_tolerance | The distance tolerance in which the current pose will be partly accepted as reached goal |
virtual bool mbf_abstract_core::AbstractController::setPlan | ( | const std::vector< geometry_msgs::PoseStamped > & | plan | ) | [pure virtual] |
Set the plan that the local planner is following.
plan | The plan to pass to the local planner |