latched_stop_rotate_controller.h
Go to the documentation of this file.
1 /*
2  * latched_stop_rotate_controller.h
3  *
4  * Created on: Apr 16, 2012
5  * Author: tkruse
6  */
7 
8 #ifndef LATCHED_STOP_ROTATE_CONTROLLER_H_
9 #define LATCHED_STOP_ROTATE_CONTROLLER_H_
10 
11 #include <string>
12 
13 #include <Eigen/Core>
14 
15 #include <tf/transform_datatypes.h>
16 
19 
20 namespace base_local_planner {
21 
23 public:
24  LatchedStopRotateController(const std::string& name = "");
26 
27  bool isPositionReached(LocalPlannerUtil* planner_util,
28  tf::Stamped<tf::Pose> global_pose);
29 
30  bool isGoalReached(LocalPlannerUtil* planner_util,
31  OdometryHelperRos& odom_helper,
32  tf::Stamped<tf::Pose> global_pose);
33 
34  void resetLatching() {
35  xy_tolerance_latch_ = false;
36  }
37 
45  bool stopWithAccLimits(const tf::Stamped<tf::Pose>& global_pose,
46  const tf::Stamped<tf::Pose>& robot_vel,
47  geometry_msgs::Twist& cmd_vel,
48  Eigen::Vector3f acc_lim,
49  double sim_period,
50  boost::function<bool (Eigen::Vector3f pos,
51  Eigen::Vector3f vel,
52  Eigen::Vector3f vel_samples)> obstacle_check);
53 
62  bool rotateToGoal(const tf::Stamped<tf::Pose>& global_pose,
63  const tf::Stamped<tf::Pose>& robot_vel,
64  double goal_th,
65  geometry_msgs::Twist& cmd_vel,
66  Eigen::Vector3f acc_lim,
67  double sim_period,
69  boost::function<bool (Eigen::Vector3f pos,
70  Eigen::Vector3f vel,
71  Eigen::Vector3f vel_samples)> obstacle_check);
72 
73  bool computeVelocityCommandsStopRotate(geometry_msgs::Twist& cmd_vel,
74  Eigen::Vector3f acc_lim,
75  double sim_period,
76  LocalPlannerUtil* planner_util,
77  OdometryHelperRos& odom_helper,
78  tf::Stamped<tf::Pose> global_pose,
79  boost::function<bool (Eigen::Vector3f pos,
80  Eigen::Vector3f vel,
81  Eigen::Vector3f vel_samples)> obstacle_check);
82 
83 private:
84  inline double sign(double x){
85  return x < 0.0 ? -1.0 : 1.0;
86  }
87 
88 
89  // whether to latch at all, and whether in this turn we have already been in goal area
92 };
93 
94 } /* namespace base_local_planner */
95 #endif /* LATCHED_STOP_ROTATE_CONTROLLER_H_ */
bool isGoalReached(LocalPlannerUtil *planner_util, OdometryHelperRos &odom_helper, tf::Stamped< tf::Pose > global_pose)
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...
bool isPositionReached(LocalPlannerUtil *planner_util, tf::Stamped< tf::Pose > global_pose)


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:44:25