32 #ifndef HECTOR_PATH_FOLLOWER_H_ 33 #define HECTOR_PATH_FOLLOWER_H_ 38 #include <geometry_msgs/PoseStamped.h> 39 #include <geometry_msgs/Twist.h> 48 bool setPlan(
const std::vector<geometry_msgs::PoseStamped>& global_plan);
52 inline double sign(
double n){
53 return n < 0.0 ? -1.0 : 1.0;
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);
61 std::vector<geometry_msgs::PoseStamped>& transformed_plan);
double min_in_place_vel_th_
unsigned int current_waypoint_
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &global_plan)
std::string p_global_frame_
geometry_msgs::Twist diff2D(const tf::Pose &pose1, const tf::Pose &pose2)
ros::Time goal_reached_time_
TFSIMD_FORCE_INLINE const tfScalar & y() const
tf::TransformListener * tf_
bool getRobotPose(tf::Stamped< tf::Pose > &global_pose) const
double rot_stopped_velocity_
double headingDiff(double pt_x, double pt_y, double x, double y, double heading)
ros::Subscriber odom_sub_
double in_place_trans_vel_
double tolerance_timeout_
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)
double trans_stopped_velocity_
std::string p_robot_base_frame_