8 #ifndef SAFE_TRAJECTORY_PLANNER_ROS_H_ 9 #define SAFE_TRAJECTORY_PLANNER_ROS_H_ 23 #include <nav_msgs/Odometry.h> 24 #include <geometry_msgs/PoseStamped.h> 25 #include <geometry_msgs/Twist.h> 26 #include <geometry_msgs/Point.h> 27 #include <std_srvs/Empty.h> 31 #include <boost/thread.hpp> 42 #if ROS_VERSION_MINIMUM(1, 14, 0) // ROS_MELODIC 89 double distance(
double x1,
double y1,
double x2,
double y2);
100 void publishPlan(
const std::vector<geometry_msgs::PoseStamped>& path,
const ros::Publisher& pub,
double r,
double g,
double b,
double a);
102 void odomCallback(
const nav_msgs::Odometry::ConstPtr& msg);
104 void cmdCallback(
const geometry_msgs::Twist::ConstPtr& vel);
double distance(double x1, double y1, double x2, double y2)
Compute the distance between two points.
SafeTrajectoryPlannerROS(TFListener *tf, costmap_2d::Costmap2DROS *costmap_ros)
Constructs the ros wrapper.
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub, double r, double g, double b, double a)
Publish a plan for visualization purposes.
double max_sensor_range_
Keep track of the effective maximum range of our sensors.
ros::ServiceServer clear_costmaps_srv_
costmap_2d::Costmap2D costmap_
The costmap the controller will use.
std::string robot_base_frame_
Used as the base frame id of the robot.
bool transformGlobalPlan(std::vector< geometry_msgs::PoseStamped > &transformed_plan)
Transforms the global plan of the robot from the planner frame to the local frame.
costmap_2d::Costmap2DROS * costmap_ros_
The ROS wrapper for the costmap the controller will use.
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
Computes control velocities for a robot given a costmap, a plan, and the robot's position in the worl...
double trans_stopped_velocity_
ros::Publisher u_plan_pub_
void cmdCallback(const geometry_msgs::Twist::ConstPtr &vel)
nav_msgs::Odometry base_odom_
Used to get the velocity of the robot.
double circumscribed_radius_
ros::Subscriber user_sub_
bool clearCostmapsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
ros::Subscriber odom_sub_
std::string global_frame_
The frame in which the controller will run.
A ROS wrapper for the trajectory controller that queries the param server to construct a controller...
bool stopped()
Check whether the robot is stopped or not.
~SafeTrajectoryPlannerROS()
Destructor for the wrapper.
std::vector< double > loadYVels(ros::NodeHandle node)
TFListener * tf_
Used for transforming point clouds.
boost::recursive_mutex odom_lock_
bool computeVelocityCommands(const geometry_msgs::Twist::ConstPtr &vel, geometry_msgs::Twist &cmd_vel)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
double rot_stopped_velocity_
base_local_planner::WorldModel * world_model_
The world model that the controller will use.
ros::Publisher l_plan_pub_
tf::TransformListener TFListener
SafeTrajectoryPlanner * tc_
The trajectory controller.