8 #ifndef LATCHED_STOP_ROTATE_CONTROLLER_H_ 9 #define LATCHED_STOP_ROTATE_CONTROLLER_H_ 47 geometry_msgs::Twist& cmd_vel,
48 Eigen::Vector3f acc_lim,
50 boost::function<
bool (Eigen::Vector3f pos,
52 Eigen::Vector3f vel_samples)> obstacle_check);
65 geometry_msgs::Twist& cmd_vel,
66 Eigen::Vector3f acc_lim,
69 boost::function<
bool (Eigen::Vector3f pos,
71 Eigen::Vector3f vel_samples)> obstacle_check);
74 Eigen::Vector3f acc_lim,
79 boost::function<
bool (Eigen::Vector3f pos,
81 Eigen::Vector3f vel_samples)> obstacle_check);
84 inline double sign(
double x){
85 return x < 0.0 ? -1.0 : 1.0;
bool isGoalReached(LocalPlannerUtil *planner_util, OdometryHelperRos &odom_helper, tf::Stamped< tf::Pose > global_pose)
LatchedStopRotateController(const std::string &name="")
bool latch_xy_goal_tolerance_
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 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.
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.
Helper class implementing infrastructure code many local planner implementations may need...
virtual ~LatchedStopRotateController()
bool isPositionReached(LocalPlannerUtil *planner_util, tf::Stamped< tf::Pose > global_pose)