#include <latched_stop_rotate_controller.h>
|
bool | computeVelocityCommandsStopRotate (geometry_msgs::Twist &cmd_vel, Eigen::Vector3f acc_lim, double sim_period, LocalPlannerUtil *planner_util, OdometryHelperRos &odom_helper, const geometry_msgs::PoseStamped &global_pose, boost::function< bool(Eigen::Vector3f pos, Eigen::Vector3f vel, Eigen::Vector3f vel_samples)> obstacle_check) |
|
bool | isGoalReached (LocalPlannerUtil *planner_util, OdometryHelperRos &odom_helper, const geometry_msgs::PoseStamped &global_pose) |
|
bool | isPositionReached (LocalPlannerUtil *planner_util, const geometry_msgs::PoseStamped &global_pose) |
|
| LatchedStopRotateController (const std::string &name="") |
|
void | resetLatching () |
|
bool | rotateToGoal (const geometry_msgs::PoseStamped &global_pose, const geometry_msgs::PoseStamped &robot_vel, double goal_th, geometry_msgs::Twist &cmd_vel, Eigen::Vector3f acc_lim, double sim_period, base_local_planner::LocalPlannerLimits &limits, boost::function< bool(Eigen::Vector3f pos, Eigen::Vector3f vel, Eigen::Vector3f vel_samples)> obstacle_check) |
| Once a goal position is reached... rotate to the goal orientation. More...
|
|
bool | stopWithAccLimits (const geometry_msgs::PoseStamped &global_pose, const geometry_msgs::PoseStamped &robot_vel, geometry_msgs::Twist &cmd_vel, Eigen::Vector3f acc_lim, double sim_period, boost::function< bool(Eigen::Vector3f pos, Eigen::Vector3f vel, Eigen::Vector3f vel_samples)> obstacle_check) |
| Stop the robot taking into account acceleration limits. More...
|
|
virtual | ~LatchedStopRotateController () |
|
◆ LatchedStopRotateController()
base_local_planner::LatchedStopRotateController::LatchedStopRotateController |
( |
const std::string & |
name = "" | ) |
|
◆ ~LatchedStopRotateController()
base_local_planner::LatchedStopRotateController::~LatchedStopRotateController |
( |
| ) |
|
|
virtual |
◆ computeVelocityCommandsStopRotate()
bool base_local_planner::LatchedStopRotateController::computeVelocityCommandsStopRotate |
( |
geometry_msgs::Twist & |
cmd_vel, |
|
|
Eigen::Vector3f |
acc_lim, |
|
|
double |
sim_period, |
|
|
LocalPlannerUtil * |
planner_util, |
|
|
OdometryHelperRos & |
odom_helper, |
|
|
const geometry_msgs::PoseStamped & |
global_pose, |
|
|
boost::function< bool(Eigen::Vector3f pos, Eigen::Vector3f vel, Eigen::Vector3f vel_samples)> |
obstacle_check |
|
) |
| |
◆ isGoalReached()
bool base_local_planner::LatchedStopRotateController::isGoalReached |
( |
LocalPlannerUtil * |
planner_util, |
|
|
OdometryHelperRos & |
odom_helper, |
|
|
const geometry_msgs::PoseStamped & |
global_pose |
|
) |
| |
returns true if we have passed the goal position and have reached goal orientation. Meaning we might have overshot on the position beyond tolerance, yet still return true.
Definition at line 66 of file latched_stop_rotate_controller.cpp.
◆ isPositionReached()
bool base_local_planner::LatchedStopRotateController::isPositionReached |
( |
LocalPlannerUtil * |
planner_util, |
|
|
const geometry_msgs::PoseStamped & |
global_pose |
|
) |
| |
returns true if we have passed the goal position. Meaning we might have overshot on the position beyond tolerance, yet still return true. Also goal orientation might not yet be true
Definition at line 39 of file latched_stop_rotate_controller.cpp.
◆ resetLatching()
void base_local_planner::LatchedStopRotateController::resetLatching |
( |
| ) |
|
|
inline |
◆ rotateToGoal()
bool base_local_planner::LatchedStopRotateController::rotateToGoal |
( |
const geometry_msgs::PoseStamped & |
global_pose, |
|
|
const geometry_msgs::PoseStamped & |
robot_vel, |
|
|
double |
goal_th, |
|
|
geometry_msgs::Twist & |
cmd_vel, |
|
|
Eigen::Vector3f |
acc_lim, |
|
|
double |
sim_period, |
|
|
base_local_planner::LocalPlannerLimits & |
limits, |
|
|
boost::function< bool(Eigen::Vector3f pos, Eigen::Vector3f vel, Eigen::Vector3f vel_samples)> |
obstacle_check |
|
) |
| |
Once a goal position is reached... rotate to the goal orientation.
- Parameters
-
global_pose | The pose of the robot in the global frame |
robot_vel | The velocity of the robot |
goal_th | The desired th value for the goal |
cmd_vel | The velocity commands to be filled |
- Returns
- True if a valid trajectory was found, false otherwise
Definition at line 148 of file latched_stop_rotate_controller.cpp.
◆ sign()
double base_local_planner::LatchedStopRotateController::sign |
( |
double |
x | ) |
|
|
inlineprivate |
◆ stopWithAccLimits()
bool base_local_planner::LatchedStopRotateController::stopWithAccLimits |
( |
const geometry_msgs::PoseStamped & |
global_pose, |
|
|
const geometry_msgs::PoseStamped & |
robot_vel, |
|
|
geometry_msgs::Twist & |
cmd_vel, |
|
|
Eigen::Vector3f |
acc_lim, |
|
|
double |
sim_period, |
|
|
boost::function< bool(Eigen::Vector3f pos, Eigen::Vector3f vel, Eigen::Vector3f vel_samples)> |
obstacle_check |
|
) |
| |
Stop the robot taking into account acceleration limits.
- Parameters
-
global_pose | The pose of the robot in the global frame |
robot_vel | The velocity of the robot |
cmd_vel | The velocity commands to be filled |
- Returns
- True if a valid trajectory was found, false otherwise
Definition at line 110 of file latched_stop_rotate_controller.cpp.
◆ latch_xy_goal_tolerance_
bool base_local_planner::LatchedStopRotateController::latch_xy_goal_tolerance_ |
|
private |
◆ rotating_to_goal_
bool base_local_planner::LatchedStopRotateController::rotating_to_goal_ |
|
private |
◆ xy_tolerance_latch_
bool base_local_planner::LatchedStopRotateController::xy_tolerance_latch_ |
|
private |
The documentation for this class was generated from the following files: