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 
17 
18 namespace base_local_planner {
19 
21 public:
22  LatchedStopRotateController(const std::string& name = "");
24 
25  bool isPositionReached(LocalPlannerUtil* planner_util,
26  const geometry_msgs::PoseStamped& global_pose);
27 
28  bool isGoalReached(LocalPlannerUtil* planner_util,
29  OdometryHelperRos& odom_helper,
30  const geometry_msgs::PoseStamped& global_pose);
31 
32  void resetLatching() {
33  xy_tolerance_latch_ = false;
34  }
35 
43  bool stopWithAccLimits(const geometry_msgs::PoseStamped& global_pose,
44  const geometry_msgs::PoseStamped& robot_vel,
45  geometry_msgs::Twist& cmd_vel,
46  Eigen::Vector3f acc_lim,
47  double sim_period,
48  boost::function<bool (Eigen::Vector3f pos,
49  Eigen::Vector3f vel,
50  Eigen::Vector3f vel_samples)> obstacle_check);
51 
60  bool rotateToGoal(const geometry_msgs::PoseStamped& global_pose,
61  const geometry_msgs::PoseStamped& robot_vel,
62  double goal_th,
63  geometry_msgs::Twist& cmd_vel,
64  Eigen::Vector3f acc_lim,
65  double sim_period,
67  boost::function<bool (Eigen::Vector3f pos,
68  Eigen::Vector3f vel,
69  Eigen::Vector3f vel_samples)> obstacle_check);
70 
71  bool computeVelocityCommandsStopRotate(geometry_msgs::Twist& cmd_vel,
72  Eigen::Vector3f acc_lim,
73  double sim_period,
74  LocalPlannerUtil* planner_util,
75  OdometryHelperRos& odom_helper,
76  const geometry_msgs::PoseStamped& global_pose,
77  boost::function<bool (Eigen::Vector3f pos,
78  Eigen::Vector3f vel,
79  Eigen::Vector3f vel_samples)> obstacle_check);
80 
81 private:
82  inline double sign(double x){
83  return x < 0.0 ? -1.0 : 1.0;
84  }
85 
86 
87  // whether to latch at all, and whether in this turn we have already been in goal area
90 };
91 
92 } /* namespace base_local_planner */
93 #endif /* LATCHED_STOP_ROTATE_CONTROLLER_H_ */
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 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.
bool isPositionReached(LocalPlannerUtil *planner_util, const geometry_msgs::PoseStamped &global_pose)
bool isGoalReached(LocalPlannerUtil *planner_util, OdometryHelperRos &odom_helper, const geometry_msgs::PoseStamped &global_pose)
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)
Helper class implementing infrastructure code many local planner implementations may need...


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Wed Jun 22 2022 02:07:08