pose_follower.h
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2009, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of Willow Garage, Inc. nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Eitan Marder-Eppstein
36 *********************************************************************/
37 #ifndef POSE_FOLLOWER_POSE_FOLLOWER_H_
38 #define POSE_FOLLOWER_POSE_FOLLOWER_H_
39 #include <ros/ros.h>
40 #include <tf/tf.h>
41 #include <tf/transform_datatypes.h>
42 #include <tf/transform_listener.h>
45 #include <geometry_msgs/PoseStamped.h>
46 #include <geometry_msgs/Twist.h>
47 #include <nav_msgs/Odometry.h>
48 #include <pose_follower/PoseFollowerConfig.h>
49 #include <dynamic_reconfigure/server.h>
51 
52 namespace pose_follower {
54  public:
55  PoseFollower();
56  ~PoseFollower();
57  void initialize(std::string name, tf::TransformListener* tf, costmap_2d::Costmap2DROS* costmap_ros);
58  bool isGoalReached();
59  bool setPlan(const std::vector<geometry_msgs::PoseStamped>& global_plan);
60  bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel);
61 
62  private:
63  inline double sign(double n){
64  return n < 0.0 ? -1.0 : 1.0;
65  }
66 
67  geometry_msgs::Twist diff2D(const tf::Pose& pose1, const tf::Pose& pose2);
68  geometry_msgs::Twist limitTwist(const geometry_msgs::Twist& twist);
69  double headingDiff(double pt_x, double pt_y, double x, double y, double heading);
70 
71  bool transformGlobalPlan(const tf::TransformListener& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan,
72  const costmap_2d::Costmap2DROS& costmap, const std::string& global_frame,
73  std::vector<geometry_msgs::PoseStamped>& transformed_plan);
74 
75  void odomCallback(const nav_msgs::Odometry::ConstPtr& msg);
76  bool stopped();
77  void publishPlan(const std::vector<geometry_msgs::PoseStamped> &path, const ros::Publisher &pub);
78  void reconfigureCB(pose_follower::PoseFollowerConfig &config, uint32_t level);
79 
83  boost::mutex odom_lock_;
85  nav_msgs::Odometry base_odom_;
87  unsigned int current_waypoint_;
88  std::vector<geometry_msgs::PoseStamped> global_plan_;
90  dynamic_reconfigure::Server<pose_follower::PoseFollowerConfig> *dsrv_;
91 
92  // Parameters
99  int samples_;
104  };
105 };
106 #endif
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
ros::Publisher global_plan_pub_
Definition: pose_follower.h:82
base_local_planner::TrajectoryPlannerROS collision_planner_
Definition: pose_follower.h:89
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub)
double headingDiff(double pt_x, double pt_y, double x, double y, double heading)
tf::TransformListener * tf_
Definition: pose_follower.h:80
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &global_plan)
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::vector< geometry_msgs::PoseStamped > global_plan_
Definition: pose_follower.h:88
bool transformGlobalPlan(const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const costmap_2d::Costmap2DROS &costmap, const std::string &global_frame, std::vector< geometry_msgs::PoseStamped > &transformed_plan)
void reconfigureCB(pose_follower::PoseFollowerConfig &config, uint32_t level)
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
TFSIMD_FORCE_INLINE const tfScalar & x() const
void initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros)
dynamic_reconfigure::Server< pose_follower::PoseFollowerConfig > * dsrv_
Definition: pose_follower.h:90
geometry_msgs::Twist diff2D(const tf::Pose &pose1, const tf::Pose &pose2)
geometry_msgs::Twist limitTwist(const geometry_msgs::Twist &twist)
costmap_2d::Costmap2DROS * costmap_ros_
Definition: pose_follower.h:81
nav_msgs::Odometry base_odom_
Definition: pose_follower.h:85


pose_follower
Author(s): Eitan Marder-Eppstein
autogenerated on Mon Jun 22 2020 03:18:15