safe_trajectory_planner_ros.h
Go to the documentation of this file.
1 /*
2  * safe_trajectory_planner.h
3  *
4  * Created on: Mar 25, 2010
5  * Author: duhadway
6  */
7 
8 #ifndef SAFE_TRAJECTORY_PLANNER_ROS_H_
9 #define SAFE_TRAJECTORY_PLANNER_ROS_H_
10 
11 #include <ros/ros.h>
12 #include <costmap_2d/costmap_2d.h>
20 
21 #include <tf/transform_datatypes.h>
22 
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>
28 
29 #include <tf/transform_listener.h>
30 
31 #include <boost/thread.hpp>
32 
33 #include <string>
34 
35 #include <angles/angles.h>
36 
38 
39 
40 namespace safe_teleop {
41 
42 #if ROS_VERSION_MINIMUM(1, 14, 0) // ROS_MELODIC
44 #else
46 #endif
47 
53  public:
60  SafeTrajectoryPlannerROS(TFListener* tf, costmap_2d::Costmap2DROS* costmap_ros);
61 
66 
73  bool computeVelocityCommands(const geometry_msgs::Twist::ConstPtr& vel, geometry_msgs::Twist& cmd_vel);
74 
75  private:
80  bool stopped();
81 
89  double distance(double x1, double y1, double x2, double y2);
90 
95  bool transformGlobalPlan(std::vector<geometry_msgs::PoseStamped>& transformed_plan);
96 
100  void publishPlan(const std::vector<geometry_msgs::PoseStamped>& path, const ros::Publisher& pub, double r, double g, double b, double a);
101 
102  void odomCallback(const nav_msgs::Odometry::ConstPtr& msg);
103 
104  void cmdCallback(const geometry_msgs::Twist::ConstPtr& vel);
105 
106  bool clearCostmapsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp);
107 
108  std::vector<double> loadYVels(ros::NodeHandle node);
109 
111 
116  TFListener* tf_;
117  std::string global_frame_;
119  nav_msgs::Odometry base_odom_;
120  std::string robot_base_frame_;
126 
129 
131 
132  boost::recursive_mutex odom_lock_;
135  };
136 
137 }
138 
139 
140 #endif /* SAFE_TRAJECTORY_PLANNER_ROS_H_ */
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.
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&#39;s position in the worl...
void cmdCallback(const geometry_msgs::Twist::ConstPtr &vel)
nav_msgs::Odometry base_odom_
Used to get the velocity of the robot.
bool clearCostmapsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
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.
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...
base_local_planner::WorldModel * world_model_
The world model that the controller will use.
tf::TransformListener TFListener
SafeTrajectoryPlanner * tc_
The trajectory controller.


safe_teleop_base
Author(s):
autogenerated on Fri Dec 20 2019 04:00:23