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 <tf2/convert.h>
42 #include <tf2/utils.h>
44 #include <tf2_ros/buffer.h>
47 #include <geometry_msgs/Pose.h>
48 #include <geometry_msgs/PoseStamped.h>
49 #include <geometry_msgs/Twist.h>
50 #include <nav_msgs/Odometry.h>
51 #include <pose_follower/PoseFollowerConfig.h>
52 #include <dynamic_reconfigure/server.h>
54 
55 namespace pose_follower {
57  public:
58  PoseFollower();
59  ~PoseFollower();
60  void initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* costmap_ros);
61  bool isGoalReached();
62  bool setPlan(const std::vector<geometry_msgs::PoseStamped>& global_plan);
63  bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel);
64 
65  private:
66  inline double sign(double n){
67  return n < 0.0 ? -1.0 : 1.0;
68  }
69 
70  geometry_msgs::Twist diff2D(const geometry_msgs::Pose& pose1, const geometry_msgs::Pose& pose2);
71  geometry_msgs::Twist limitTwist(const geometry_msgs::Twist& twist);
72  double headingDiff(double pt_x, double pt_y, double x, double y, double heading);
73 
74  bool transformGlobalPlan(const tf2_ros::Buffer& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan,
75  const costmap_2d::Costmap2DROS& costmap, const std::string& global_frame,
76  std::vector<geometry_msgs::PoseStamped>& transformed_plan);
77 
78  void odomCallback(const nav_msgs::Odometry::ConstPtr& msg);
79  bool stopped();
80  void publishPlan(const std::vector<geometry_msgs::PoseStamped> &path, const ros::Publisher &pub);
81  void reconfigureCB(pose_follower::PoseFollowerConfig &config, uint32_t level);
82 
86  boost::mutex odom_lock_;
88  nav_msgs::Odometry base_odom_;
90  unsigned int current_waypoint_;
91  std::vector<geometry_msgs::PoseStamped> global_plan_;
93  dynamic_reconfigure::Server<pose_follower::PoseFollowerConfig> *dsrv_;
94 
95  // Parameters
96  double max_vel_lin_, max_vel_th_;
97  double min_vel_lin_, min_vel_th_;
101  double tolerance_timeout_;
102  int samples_;
103  bool allow_backwards_;
106  bool holonomic_;
107  };
108 };
109 #endif
pose_follower::PoseFollower::transformGlobalPlan
bool transformGlobalPlan(const tf2_ros::Buffer &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)
Definition: pose_follower.cpp:398
pose_follower::PoseFollower::isGoalReached
bool isGoalReached()
Definition: pose_follower.cpp:290
pose_follower::PoseFollower::stopped
bool stopped()
Definition: pose_follower.cpp:161
ros::Publisher
pose_follower::PoseFollower::K_trans_
double K_trans_
Definition: pose_follower.h:170
pose_follower::PoseFollower::global_plan_
std::vector< geometry_msgs::PoseStamped > global_plan_
Definition: pose_follower.h:161
pose_follower::PoseFollower::min_vel_th_
double min_vel_th_
Definition: pose_follower.h:167
pose_follower::PoseFollower::rot_stopped_velocity_
double rot_stopped_velocity_
Definition: pose_follower.h:169
utils.h
base_local_planner::TrajectoryPlannerROS
ros.h
trajectory_planner_ros.h
pose_follower::PoseFollower::dsrv_
dynamic_reconfigure::Server< pose_follower::PoseFollowerConfig > * dsrv_
Definition: pose_follower.h:163
pose_follower::PoseFollower::headingDiff
double headingDiff(double pt_x, double pt_y, double x, double y, double heading)
Definition: pose_follower.cpp:145
pose_follower::PoseFollower::collision_planner_
base_local_planner::TrajectoryPlannerROS collision_planner_
Definition: pose_follower.h:162
buffer.h
pose_follower::PoseFollower::tf_
tf2_ros::Buffer * tf_
Definition: pose_follower.h:153
pose_follower::PoseFollower::odomCallback
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
Definition: pose_follower.cpp:135
costmap_2d_ros.h
pose_follower::PoseFollower::odom_lock_
boost::mutex odom_lock_
Definition: pose_follower.h:156
pose_follower::PoseFollower::turn_in_place_first_
bool turn_in_place_first_
Definition: pose_follower.h:174
pose_follower::PoseFollower::K_rot_
double K_rot_
Definition: pose_follower.h:170
pose_follower::PoseFollower::holonomic_
bool holonomic_
Definition: pose_follower.h:176
pose_follower::PoseFollower::computeVelocityCommands
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
Definition: pose_follower.cpp:193
pose_follower::PoseFollower::sign
double sign(double n)
Definition: pose_follower.h:136
pose_follower::PoseFollower::goal_reached_time_
ros::Time goal_reached_time_
Definition: pose_follower.h:159
pose_follower
Definition: pose_follower.h:55
base_local_planner.h
pose_follower::PoseFollower::~PoseFollower
~PoseFollower()
Definition: pose_follower.cpp:81
pose_follower::PoseFollower::costmap_ros_
costmap_2d::Costmap2DROS * costmap_ros_
Definition: pose_follower.h:154
pose_follower::PoseFollower::max_vel_th_
double max_vel_th_
Definition: pose_follower.h:166
pose_follower::PoseFollower::tolerance_trans_
double tolerance_trans_
Definition: pose_follower.h:170
pose_follower::PoseFollower::trans_stopped_velocity_
double trans_stopped_velocity_
Definition: pose_follower.h:169
pose_follower::PoseFollower::setPlan
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &global_plan)
Definition: pose_follower.cpp:277
tf2_ros::Buffer
pose_follower::PoseFollower::PoseFollower
PoseFollower()
Definition: pose_follower.cpp:79
pose_follower::PoseFollower::samples_
int samples_
Definition: pose_follower.h:172
pose_follower::PoseFollower::diff2D
geometry_msgs::Twist diff2D(const geometry_msgs::Pose &pose1, const geometry_msgs::Pose &pose2)
Definition: pose_follower.cpp:294
pose_follower::PoseFollower::tolerance_timeout_
double tolerance_timeout_
Definition: pose_follower.h:171
pose_follower::PoseFollower::current_waypoint_
unsigned int current_waypoint_
Definition: pose_follower.h:160
pose_follower::PoseFollower::min_vel_lin_
double min_vel_lin_
Definition: pose_follower.h:167
pose_follower::PoseFollower::in_place_trans_vel_
double in_place_trans_vel_
Definition: pose_follower.h:168
pose_follower::PoseFollower::base_odom_
nav_msgs::Odometry base_odom_
Definition: pose_follower.h:158
transform_datatypes.h
pose_follower::PoseFollower::min_in_place_vel_th_
double min_in_place_vel_th_
Definition: pose_follower.h:168
ros::Time
pose_follower::PoseFollower
Definition: pose_follower.h:91
pose_follower::PoseFollower::tolerance_rot_
double tolerance_rot_
Definition: pose_follower.h:170
pose_follower::PoseFollower::global_plan_pub_
ros::Publisher global_plan_pub_
Definition: pose_follower.h:155
tf2_geometry_msgs.h
tf
convert.h
pose_follower::PoseFollower::max_heading_diff_before_moving_
double max_heading_diff_before_moving_
Definition: pose_follower.h:175
pose_follower::PoseFollower::reconfigureCB
void reconfigureCB(pose_follower::PoseFollowerConfig &config, uint32_t level)
Definition: pose_follower.cpp:112
pose_follower::PoseFollower::odom_sub_
ros::Subscriber odom_sub_
Definition: pose_follower.h:157
pose_follower::PoseFollower::initialize
void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros)
Definition: pose_follower.cpp:86
pose_follower::PoseFollower::publishPlan
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub)
Definition: pose_follower.cpp:174
pose_follower::PoseFollower::limitTwist
geometry_msgs::Twist limitTwist(const geometry_msgs::Twist &twist)
Definition: pose_follower.cpp:344
costmap_2d::Costmap2DROS
pose_follower::PoseFollower::max_vel_lin_
double max_vel_lin_
Definition: pose_follower.h:166
nav_core::BaseLocalPlanner
ros::Subscriber
pose_follower::PoseFollower::allow_backwards_
bool allow_backwards_
Definition: pose_follower.h:173


pose_follower
Author(s): Eitan Marder-Eppstein
autogenerated on Fri Aug 26 2022 02:17:51