Public Member Functions | Private Member Functions | Private Attributes
base_local_planner::LatchedStopRotateController Class Reference

#include <latched_stop_rotate_controller.h>

List of all members.

Public Member Functions

bool computeVelocityCommandsStopRotate (geometry_msgs::Twist &cmd_vel, Eigen::Vector3f acc_lim, double sim_period, LocalPlannerUtil *planner_util, OdometryHelperRos &odom_helper, tf::Stamped< tf::Pose > 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, tf::Stamped< tf::Pose > global_pose)
bool isPositionReached (LocalPlannerUtil *planner_util, tf::Stamped< tf::Pose > global_pose)
 LatchedStopRotateController (const std::string &name="")
void resetLatching ()
bool rotateToGoal (const tf::Stamped< tf::Pose > &global_pose, const tf::Stamped< tf::Pose > &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.
bool stopWithAccLimits (const tf::Stamped< tf::Pose > &global_pose, const tf::Stamped< tf::Pose > &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.
virtual ~LatchedStopRotateController ()

Private Member Functions

double sign (double x)

Private Attributes

bool latch_xy_goal_tolerance_
bool rotating_to_goal_
bool xy_tolerance_latch_

Detailed Description

Definition at line 22 of file latched_stop_rotate_controller.h.


Constructor & Destructor Documentation

Definition at line 22 of file latched_stop_rotate_controller.cpp.

Definition at line 29 of file latched_stop_rotate_controller.cpp.


Member Function Documentation

bool base_local_planner::LatchedStopRotateController::computeVelocityCommandsStopRotate ( geometry_msgs::Twist &  cmd_vel,
Eigen::Vector3f  acc_lim,
double  sim_period,
LocalPlannerUtil planner_util,
OdometryHelperRos odom_helper,
tf::Stamped< tf::Pose global_pose,
boost::function< bool(Eigen::Vector3f pos, Eigen::Vector3f vel, Eigen::Vector3f vel_samples)>  obstacle_check 
)

Definition at line 197 of file latched_stop_rotate_controller.cpp.

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 64 of file latched_stop_rotate_controller.cpp.

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 37 of file latched_stop_rotate_controller.cpp.

Definition at line 34 of file latched_stop_rotate_controller.h.

bool base_local_planner::LatchedStopRotateController::rotateToGoal ( const tf::Stamped< tf::Pose > &  global_pose,
const tf::Stamped< tf::Pose > &  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_poseThe pose of the robot in the global frame
robot_velThe velocity of the robot
goal_thThe desired th value for the goal
cmd_velThe velocity commands to be filled
Returns:
True if a valid trajectory was found, false otherwise

Definition at line 146 of file latched_stop_rotate_controller.cpp.

double base_local_planner::LatchedStopRotateController::sign ( double  x) [inline, private]

Definition at line 84 of file latched_stop_rotate_controller.h.

bool base_local_planner::LatchedStopRotateController::stopWithAccLimits ( const tf::Stamped< tf::Pose > &  global_pose,
const tf::Stamped< tf::Pose > &  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_poseThe pose of the robot in the global frame
robot_velThe velocity of the robot
cmd_velThe velocity commands to be filled
Returns:
True if a valid trajectory was found, false otherwise

Definition at line 108 of file latched_stop_rotate_controller.cpp.


Member Data Documentation

Definition at line 90 of file latched_stop_rotate_controller.h.

Definition at line 91 of file latched_stop_rotate_controller.h.

Definition at line 90 of file latched_stop_rotate_controller.h.


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


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Wed Aug 2 2017 03:12:38