Go to the documentation of this file.
8 #ifndef LATCHED_STOP_ROTATE_CONTROLLER_H_
9 #define LATCHED_STOP_ROTATE_CONTROLLER_H_
26 const geometry_msgs::PoseStamped& global_pose);
30 const geometry_msgs::PoseStamped& global_pose);
44 const geometry_msgs::PoseStamped& robot_vel,
45 geometry_msgs::Twist& cmd_vel,
46 Eigen::Vector3f acc_lim,
48 boost::function<
bool (Eigen::Vector3f pos,
50 Eigen::Vector3f vel_samples)> obstacle_check);
60 bool rotateToGoal(
const geometry_msgs::PoseStamped& global_pose,
61 const geometry_msgs::PoseStamped& robot_vel,
63 geometry_msgs::Twist& cmd_vel,
64 Eigen::Vector3f acc_lim,
67 boost::function<
bool (Eigen::Vector3f pos,
69 Eigen::Vector3f vel_samples)> obstacle_check);
72 Eigen::Vector3f acc_lim,
76 const geometry_msgs::PoseStamped& global_pose,
77 boost::function<
bool (Eigen::Vector3f pos,
79 Eigen::Vector3f vel_samples)> obstacle_check);
82 inline double sign(
double x){
83 return x < 0.0 ? -1.0 : 1.0;
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 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.
Helper class implementing infrastructure code many local planner implementations may need.
bool isPositionReached(LocalPlannerUtil *planner_util, const geometry_msgs::PoseStamped &global_pose)
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.
bool isGoalReached(LocalPlannerUtil *planner_util, OdometryHelperRos &odom_helper, const geometry_msgs::PoseStamped &global_pose)
virtual ~LatchedStopRotateController()
LatchedStopRotateController(const std::string &name="")
bool latch_xy_goal_tolerance_
base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:24