hector_path_follower.h
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2012, Stefan Kohlbrecher, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Simulation, Systems Optimization and Robotics
13 // group, TU Darmstadt nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 /*********************************************************************
30 * Based heavily on the pose_follower package
31 *********************************************************************/
32 #ifndef HECTOR_PATH_FOLLOWER_H_
33 #define HECTOR_PATH_FOLLOWER_H_
34 #include <ros/ros.h>
35 #include <tf/tf.h>
36 #include <tf/transform_datatypes.h>
37 #include <tf/transform_listener.h>
38 #include <geometry_msgs/PoseStamped.h>
39 #include <geometry_msgs/Twist.h>
40 
41 namespace pose_follower {
43  {
44  public:
47  bool isGoalReached();
48  bool setPlan(const std::vector<geometry_msgs::PoseStamped>& global_plan);
49  bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel);
50 
51  private:
52  inline double sign(double n){
53  return n < 0.0 ? -1.0 : 1.0;
54  }
55 
56  geometry_msgs::Twist diff2D(const tf::Pose& pose1, const tf::Pose& pose2);
57  geometry_msgs::Twist limitTwist(const geometry_msgs::Twist& twist);
58  double headingDiff(double pt_x, double pt_y, double x, double y, double heading);
59 
60  bool transformGlobalPlan(const tf::TransformListener& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan, const std::string& global_frame,
61  std::vector<geometry_msgs::PoseStamped>& transformed_plan);
62 
63  //void odomCallback(const nav_msgs::Odometry::ConstPtr& msg);
64  bool stopped();
65 
66  bool getRobotPose(tf::Stamped<tf::Pose>& global_pose) const;
67 
69 
75  bool holonomic_;
76  std::string p_robot_base_frame_;
77  std::string p_global_frame_;
78 
79  boost::mutex odom_lock_;
81  //nav_msgs::Odometry base_odom_;
84  unsigned int current_waypoint_;
85  std::vector<geometry_msgs::PoseStamped> global_plan_;
86  //base_local_planner::TrajectoryPlannerROS collision_planner_;
87  int samples_;
88  };
89 };
90 #endif
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &global_plan)
geometry_msgs::Twist diff2D(const tf::Pose &pose1, const tf::Pose &pose2)
TFSIMD_FORCE_INLINE const tfScalar & y() const
bool getRobotPose(tf::Stamped< tf::Pose > &global_pose) const
double headingDiff(double pt_x, double pt_y, double x, double y, double heading)
TFSIMD_FORCE_INLINE const tfScalar & x() const
bool transformGlobalPlan(const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const std::string &global_frame, std::vector< geometry_msgs::PoseStamped > &transformed_plan)
void initialize(tf::TransformListener *tf)
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
std::vector< geometry_msgs::PoseStamped > global_plan_
geometry_msgs::Twist limitTwist(const geometry_msgs::Twist &twist)


hector_path_follower
Author(s):
autogenerated on Mon Jun 10 2019 13:34:49