A ROS wrapper for the trajectory controller that queries the param server to construct a controller. More...
#include <safe_trajectory_planner_ros.h>
Public Member Functions | |
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 to the base. | |
SafeTrajectoryPlannerROS (TFListener *tf, costmap_2d::Costmap2DROS *costmap_ros) | |
Constructs the ros wrapper. | |
~SafeTrajectoryPlannerROS () | |
Destructor for the wrapper. | |
Private Member Functions | |
void | cmdCallback (const geometry_msgs::Twist::ConstPtr &vel) |
double | distance (double x1, double y1, double x2, double y2) |
Compute the distance between two points. | |
std::vector< double > | loadYVels (ros::NodeHandle node) |
void | odomCallback (const nav_msgs::Odometry::ConstPtr &msg) |
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. | |
bool | stopped () |
Check whether the robot is stopped or not. | |
bool | transformGlobalPlan (std::vector< geometry_msgs::PoseStamped > &transformed_plan) |
Transforms the global plan of the robot from the planner frame to the local frame. | |
Private Attributes | |
nav_msgs::Odometry | base_odom_ |
Used to get the velocity of the robot. | |
double | circumscribed_radius_ |
ros::Publisher | cmd_pub_ |
ros::Subscriber | cmd_sub_ |
costmap_2d::Costmap2D | costmap_ |
The costmap the controller will use. | |
costmap_2d::Costmap2DROS * | costmap_ros_ |
The ROS wrapper for the costmap the controller will use. | |
std::string | global_frame_ |
The frame in which the controller will run. | |
double | inscribed_radius_ |
ros::Publisher | l_plan_pub_ |
double | max_sensor_range_ |
Keep track of the effective maximum range of our sensors. | |
double | max_vel_th_ |
double | min_vel_th_ |
ros::NodeHandle | nh_ |
boost::recursive_mutex | odom_lock_ |
ros::Subscriber | odom_sub_ |
std::string | robot_base_frame_ |
Used as the base frame id of the robot. | |
double | rot_stopped_velocity_ |
SafeTrajectoryPlanner * | tc_ |
The trajectory controller. | |
TFListener * | tf_ |
Used for transforming point clouds. | |
double | trans_stopped_velocity_ |
ros::Publisher | u_plan_pub_ |
ros::Subscriber | user_sub_ |
base_local_planner::WorldModel * | world_model_ |
The world model that the controller will use. |
A ROS wrapper for the trajectory controller that queries the param server to construct a controller.
Definition at line 51 of file safe_trajectory_planner_ros.h.
safe_teleop::SafeTrajectoryPlannerROS::SafeTrajectoryPlannerROS | ( | TFListener * | tf, |
costmap_2d::Costmap2DROS * | costmap_ros | ||
) |
Constructs the ros wrapper.
name | The name to give this instance of the trajectory planner |
tf | A pointer to a transform listener |
costmap | The cost map to use for assigning costs to trajectories |
Definition at line 21 of file safe_trajectory_planner_ros.cpp.
Destructor for the wrapper.
Definition at line 132 of file safe_trajectory_planner_ros.cpp.
void safe_teleop::SafeTrajectoryPlannerROS::cmdCallback | ( | const geometry_msgs::Twist::ConstPtr & | vel | ) | [private] |
Definition at line 161 of file safe_trajectory_planner_ros.cpp.
bool safe_teleop::SafeTrajectoryPlannerROS::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 to the base.
vel | Velocity received from user |
cmd_vel | Will be filled with the velocity command to be passed to the robot base |
Definition at line 184 of file safe_trajectory_planner_ros.cpp.
double safe_teleop::SafeTrajectoryPlannerROS::distance | ( | double | x1, |
double | y1, | ||
double | x2, | ||
double | y2 | ||
) | [private] |
Compute the distance between two points.
x1 | The first x point |
y1 | The first y point |
x2 | The second x point |
y2 | The second y point |
Definition at line 147 of file safe_trajectory_planner_ros.cpp.
std::vector< double > safe_teleop::SafeTrajectoryPlannerROS::loadYVels | ( | ros::NodeHandle | node | ) | [private] |
Definition at line 101 of file safe_trajectory_planner_ros.cpp.
void safe_teleop::SafeTrajectoryPlannerROS::odomCallback | ( | const nav_msgs::Odometry::ConstPtr & | msg | ) | [private] |
Definition at line 151 of file safe_trajectory_planner_ros.cpp.
void safe_teleop::SafeTrajectoryPlannerROS::publishPlan | ( | const std::vector< geometry_msgs::PoseStamped > & | path, |
const ros::Publisher & | pub, | ||
double | r, | ||
double | g, | ||
double | b, | ||
double | a | ||
) | [private] |
Publish a plan for visualization purposes.
Definition at line 286 of file safe_trajectory_planner_ros.cpp.
bool safe_teleop::SafeTrajectoryPlannerROS::stopped | ( | ) | [private] |
Check whether the robot is stopped or not.
Definition at line 140 of file safe_trajectory_planner_ros.cpp.
bool safe_teleop::SafeTrajectoryPlannerROS::transformGlobalPlan | ( | std::vector< geometry_msgs::PoseStamped > & | transformed_plan | ) | [private] |
Transforms the global plan of the robot from the planner frame to the local frame.
transformed_plan | Populated with the transformed plan |
nav_msgs::Odometry safe_teleop::SafeTrajectoryPlannerROS::base_odom_ [private] |
Used to get the velocity of the robot.
Definition at line 116 of file safe_trajectory_planner_ros.h.
double safe_teleop::SafeTrajectoryPlannerROS::circumscribed_radius_ [private] |
Definition at line 119 of file safe_trajectory_planner_ros.h.
Definition at line 124 of file safe_trajectory_planner_ros.h.
Definition at line 125 of file safe_trajectory_planner_ros.h.
The costmap the controller will use.
Definition at line 112 of file safe_trajectory_planner_ros.h.
The ROS wrapper for the costmap the controller will use.
Definition at line 111 of file safe_trajectory_planner_ros.h.
std::string safe_teleop::SafeTrajectoryPlannerROS::global_frame_ [private] |
The frame in which the controller will run.
Definition at line 114 of file safe_trajectory_planner_ros.h.
double safe_teleop::SafeTrajectoryPlannerROS::inscribed_radius_ [private] |
Definition at line 119 of file safe_trajectory_planner_ros.h.
Definition at line 120 of file safe_trajectory_planner_ros.h.
double safe_teleop::SafeTrajectoryPlannerROS::max_sensor_range_ [private] |
Keep track of the effective maximum range of our sensors.
Definition at line 115 of file safe_trajectory_planner_ros.h.
double safe_teleop::SafeTrajectoryPlannerROS::max_vel_th_ [private] |
Definition at line 128 of file safe_trajectory_planner_ros.h.
double safe_teleop::SafeTrajectoryPlannerROS::min_vel_th_ [private] |
Definition at line 128 of file safe_trajectory_planner_ros.h.
Definition at line 107 of file safe_trajectory_planner_ros.h.
boost::recursive_mutex safe_teleop::SafeTrajectoryPlannerROS::odom_lock_ [private] |
Definition at line 127 of file safe_trajectory_planner_ros.h.
Definition at line 122 of file safe_trajectory_planner_ros.h.
std::string safe_teleop::SafeTrajectoryPlannerROS::robot_base_frame_ [private] |
Used as the base frame id of the robot.
Definition at line 117 of file safe_trajectory_planner_ros.h.
double safe_teleop::SafeTrajectoryPlannerROS::rot_stopped_velocity_ [private] |
Definition at line 118 of file safe_trajectory_planner_ros.h.
The trajectory controller.
Definition at line 110 of file safe_trajectory_planner_ros.h.
Used for transforming point clouds.
Definition at line 113 of file safe_trajectory_planner_ros.h.
double safe_teleop::SafeTrajectoryPlannerROS::trans_stopped_velocity_ [private] |
Definition at line 118 of file safe_trajectory_planner_ros.h.
Definition at line 121 of file safe_trajectory_planner_ros.h.
Definition at line 122 of file safe_trajectory_planner_ros.h.
The world model that the controller will use.
Definition at line 109 of file safe_trajectory_planner_ros.h.