37 #ifndef POSE_FOLLOWER_POSE_FOLLOWER_H_ 38 #define POSE_FOLLOWER_POSE_FOLLOWER_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> 62 bool setPlan(
const std::vector<geometry_msgs::PoseStamped>& global_plan);
66 inline double sign(
double n){
67 return n < 0.0 ? -1.0 : 1.0;
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);
76 std::vector<geometry_msgs::PoseStamped>& transformed_plan);
78 void odomCallback(
const nav_msgs::Odometry::ConstPtr& msg);
81 void reconfigureCB(pose_follower::PoseFollowerConfig &config, uint32_t level);
93 dynamic_reconfigure::Server<pose_follower::PoseFollowerConfig> *
dsrv_;
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
ros::Publisher global_plan_pub_
ros::Subscriber odom_sub_
base_local_planner::TrajectoryPlannerROS collision_planner_
unsigned int current_waypoint_
bool turn_in_place_first_
ros::Time goal_reached_time_
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub)
double max_heading_diff_before_moving_
double trans_stopped_velocity_
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)
double headingDiff(double pt_x, double pt_y, double x, double y, double heading)
void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros)
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &global_plan)
geometry_msgs::Twist diff2D(const geometry_msgs::Pose &pose1, const geometry_msgs::Pose &pose2)
std::vector< geometry_msgs::PoseStamped > global_plan_
double tolerance_timeout_
void reconfigureCB(pose_follower::PoseFollowerConfig &config, uint32_t level)
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
double in_place_trans_vel_
double rot_stopped_velocity_
dynamic_reconfigure::Server< pose_follower::PoseFollowerConfig > * dsrv_
geometry_msgs::Twist limitTwist(const geometry_msgs::Twist &twist)
double min_in_place_vel_th_
costmap_2d::Costmap2DROS * costmap_ros_
nav_msgs::Odometry base_odom_