A ROS wrapper for the trajectory controller that queries the param server to construct a controller. More...
#include <trajectory_planner_ros.h>
Public Member Functions | |
bool | checkTrajectory (double vx_samp, double vy_samp, double vtheta_samp, bool update_map=true) |
Generate and score a single trajectory. | |
bool | computeVelocityCommands (geometry_msgs::Twist &cmd_vel) |
Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base. | |
void | initialize (std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros) |
Constructs the ros wrapper. | |
bool | isGoalReached () |
Check if the goal pose has been achieved. | |
double | scoreTrajectory (double vx_samp, double vy_samp, double vtheta_samp, bool update_map=true) |
Generate and score a single trajectory. | |
bool | setPlan (const std::vector< geometry_msgs::PoseStamped > &orig_global_plan) |
Set the plan that the controller is following. | |
TrajectoryPlannerROS (std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros) | |
Constructs the ros wrapper. | |
TrajectoryPlannerROS () | |
Default constructor for the ros wrapper. | |
~TrajectoryPlannerROS () | |
Destructor for the wrapper. | |
Private Member Functions | |
std::vector< double > | loadYVels (ros::NodeHandle node) |
void | odomCallback (const nav_msgs::Odometry::ConstPtr &msg) |
bool | rotateToGoal (const tf::Stamped< tf::Pose > &global_pose, const tf::Stamped< tf::Pose > &robot_vel, double goal_th, geometry_msgs::Twist &cmd_vel) |
Once a goal position is reached... rotate to the goal orientation. | |
double | sign (double x) |
bool | stopWithAccLimits (const tf::Stamped< tf::Pose > &global_pose, const tf::Stamped< tf::Pose > &robot_vel, geometry_msgs::Twist &cmd_vel) |
Stop the robot taking into account acceleration limits. | |
Private Attributes | |
double | acc_lim_theta_ |
double | acc_lim_x_ |
double | acc_lim_y_ |
nav_msgs::Odometry | base_odom_ |
Used to get the velocity of the robot. | |
double | circumscribed_radius_ |
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. | |
ros::Publisher | g_plan_pub_ |
std::string | global_frame_ |
The frame in which the controller will run. | |
std::vector < geometry_msgs::PoseStamped > | global_plan_ |
double | inflation_radius_ |
bool | initialized_ |
double | inscribed_radius_ |
ros::Publisher | l_plan_pub_ |
bool | latch_xy_goal_tolerance_ |
MapGridVisualizer | map_viz_ |
The map grid visualizer for outputting the potential field generated by the cost function. | |
double | max_sensor_range_ |
Keep track of the effective maximum range of our sensors. | |
double | max_vel_th_ |
double | min_in_place_vel_th_ |
double | min_vel_th_ |
boost::recursive_mutex | odom_lock_ |
ros::Subscriber | odom_sub_ |
bool | prune_plan_ |
std::string | robot_base_frame_ |
Used as the base frame id of the robot. | |
double | rot_stopped_velocity_ |
bool | rotating_to_goal_ |
double | sim_period_ |
TrajectoryPlanner * | tc_ |
The trajectory controller. | |
tf::TransformListener * | tf_ |
Used for transforming point clouds. | |
double | trans_stopped_velocity_ |
WorldModel * | world_model_ |
The world model that the controller will use. | |
double | xy_goal_tolerance_ |
bool | xy_tolerance_latch_ |
double | yaw_goal_tolerance_ |
A ROS wrapper for the trajectory controller that queries the param server to construct a controller.
Definition at line 74 of file trajectory_planner_ros.h.
base_local_planner::TrajectoryPlannerROS::TrajectoryPlannerROS | ( | ) |
Default constructor for the ros wrapper.
Definition at line 55 of file trajectory_planner_ros.cpp.
base_local_planner::TrajectoryPlannerROS::TrajectoryPlannerROS | ( | std::string | name, | |
tf::TransformListener * | 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 |
base_local_planner::TrajectoryPlannerROS::~TrajectoryPlannerROS | ( | ) |
Destructor for the wrapper.
Definition at line 251 of file trajectory_planner_ros.cpp.
bool base_local_planner::TrajectoryPlannerROS::checkTrajectory | ( | double | vx_samp, | |
double | vy_samp, | |||
double | vtheta_samp, | |||
bool | update_map = true | |||
) |
Generate and score a single trajectory.
vx_samp | The x velocity used to seed the trajectory | |
vy_samp | The y velocity used to seed the trajectory | |
vtheta_samp | The theta velocity used to seed the trajectory | |
update_map | Whether or not to update the map for the planner when computing the legality of the trajectory, this is useful to set to false if you're going to be doing a lot of trajectory checking over a short period of time |
Definition at line 517 of file trajectory_planner_ros.cpp.
bool base_local_planner::TrajectoryPlannerROS::computeVelocityCommands | ( | geometry_msgs::Twist & | cmd_vel | ) |
Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base.
cmd_vel | Will be filled with the velocity command to be passed to the robot base |
Definition at line 352 of file trajectory_planner_ros.cpp.
void base_local_planner::TrajectoryPlannerROS::initialize | ( | std::string | name, | |
tf::TransformListener * | 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 |
bool base_local_planner::TrajectoryPlannerROS::isGoalReached | ( | ) |
Check if the goal pose has been achieved.
Definition at line 591 of file trajectory_planner_ros.cpp.
std::vector< double > base_local_planner::TrajectoryPlannerROS::loadYVels | ( | ros::NodeHandle | node | ) | [private] |
Definition at line 220 of file trajectory_planner_ros.cpp.
void base_local_planner::TrajectoryPlannerROS::odomCallback | ( | const nav_msgs::Odometry::ConstPtr & | msg | ) | [private] |
Definition at line 326 of file trajectory_planner_ros.cpp.
bool base_local_planner::TrajectoryPlannerROS::rotateToGoal | ( | const tf::Stamped< tf::Pose > & | global_pose, | |
const tf::Stamped< tf::Pose > & | robot_vel, | |||
double | goal_th, | |||
geometry_msgs::Twist & | cmd_vel | |||
) | [private] |
Once a goal position is reached... rotate to the goal orientation.
global_pose | The pose of the robot in the global frame | |
robot_vel | The velocity of the robot | |
goal_th | The desired th value for the goal | |
cmd_vel | The velocity commands to be filled |
Definition at line 288 of file trajectory_planner_ros.cpp.
double base_local_planner::TrajectoryPlannerROS::scoreTrajectory | ( | double | vx_samp, | |
double | vy_samp, | |||
double | vtheta_samp, | |||
bool | update_map = true | |||
) |
Generate and score a single trajectory.
vx_samp | The x velocity used to seed the trajectory | |
vy_samp | The y velocity used to seed the trajectory | |
vtheta_samp | The theta velocity used to seed the trajectory | |
update_map | Whether or not to update the map for the planner when computing the legality of the trajectory, this is useful to set to false if you're going to be doing a lot of trajectory checking over a short period of time |
Definition at line 554 of file trajectory_planner_ros.cpp.
bool base_local_planner::TrajectoryPlannerROS::setPlan | ( | const std::vector< geometry_msgs::PoseStamped > & | orig_global_plan | ) |
Set the plan that the controller is following.
orig_global_plan | The plan to pass to the controller |
Definition at line 336 of file trajectory_planner_ros.cpp.
double base_local_planner::TrajectoryPlannerROS::sign | ( | double | x | ) | [inline, private] |
Definition at line 174 of file trajectory_planner_ros.h.
bool base_local_planner::TrajectoryPlannerROS::stopWithAccLimits | ( | const tf::Stamped< tf::Pose > & | global_pose, | |
const tf::Stamped< tf::Pose > & | robot_vel, | |||
geometry_msgs::Twist & | cmd_vel | |||
) | [private] |
Stop the robot taking into account acceleration limits.
global_pose | The pose of the robot in the global frame | |
robot_vel | The velocity of the robot | |
cmd_vel | The velocity commands to be filled |
Definition at line 259 of file trajectory_planner_ros.cpp.
double base_local_planner::TrajectoryPlannerROS::acc_lim_theta_ [private] |
Definition at line 198 of file trajectory_planner_ros.h.
double base_local_planner::TrajectoryPlannerROS::acc_lim_x_ [private] |
Definition at line 198 of file trajectory_planner_ros.h.
double base_local_planner::TrajectoryPlannerROS::acc_lim_y_ [private] |
Definition at line 198 of file trajectory_planner_ros.h.
nav_msgs::Odometry base_local_planner::TrajectoryPlannerROS::base_odom_ [private] |
Used to get the velocity of the robot.
Definition at line 186 of file trajectory_planner_ros.h.
double base_local_planner::TrajectoryPlannerROS::circumscribed_radius_ [private] |
Definition at line 190 of file trajectory_planner_ros.h.
costmap_2d::Costmap2D base_local_planner::TrajectoryPlannerROS::costmap_ [private] |
The costmap the controller will use.
Definition at line 181 of file trajectory_planner_ros.h.
costmap_2d::Costmap2DROS* base_local_planner::TrajectoryPlannerROS::costmap_ros_ [private] |
The ROS wrapper for the costmap the controller will use.
Definition at line 180 of file trajectory_planner_ros.h.
ros::Publisher base_local_planner::TrajectoryPlannerROS::g_plan_pub_ [private] |
Definition at line 193 of file trajectory_planner_ros.h.
std::string base_local_planner::TrajectoryPlannerROS::global_frame_ [private] |
The frame in which the controller will run.
Definition at line 184 of file trajectory_planner_ros.h.
std::vector<geometry_msgs::PoseStamped> base_local_planner::TrajectoryPlannerROS::global_plan_ [private] |
Definition at line 191 of file trajectory_planner_ros.h.
double base_local_planner::TrajectoryPlannerROS::inflation_radius_ [private] |
Definition at line 190 of file trajectory_planner_ros.h.
bool base_local_planner::TrajectoryPlannerROS::initialized_ [private] |
Definition at line 196 of file trajectory_planner_ros.h.
double base_local_planner::TrajectoryPlannerROS::inscribed_radius_ [private] |
Definition at line 190 of file trajectory_planner_ros.h.
ros::Publisher base_local_planner::TrajectoryPlannerROS::l_plan_pub_ [private] |
Definition at line 193 of file trajectory_planner_ros.h.
Definition at line 201 of file trajectory_planner_ros.h.
The map grid visualizer for outputting the potential field generated by the cost function.
Definition at line 182 of file trajectory_planner_ros.h.
double base_local_planner::TrajectoryPlannerROS::max_sensor_range_ [private] |
Keep track of the effective maximum range of our sensors.
Definition at line 185 of file trajectory_planner_ros.h.
double base_local_planner::TrajectoryPlannerROS::max_vel_th_ [private] |
Definition at line 197 of file trajectory_planner_ros.h.
double base_local_planner::TrajectoryPlannerROS::min_in_place_vel_th_ [private] |
Definition at line 189 of file trajectory_planner_ros.h.
double base_local_planner::TrajectoryPlannerROS::min_vel_th_ [private] |
Definition at line 197 of file trajectory_planner_ros.h.
boost::recursive_mutex base_local_planner::TrajectoryPlannerROS::odom_lock_ [private] |
Definition at line 195 of file trajectory_planner_ros.h.
ros::Subscriber base_local_planner::TrajectoryPlannerROS::odom_sub_ [private] |
Definition at line 194 of file trajectory_planner_ros.h.
bool base_local_planner::TrajectoryPlannerROS::prune_plan_ [private] |
Definition at line 192 of file trajectory_planner_ros.h.
std::string base_local_planner::TrajectoryPlannerROS::robot_base_frame_ [private] |
Used as the base frame id of the robot.
Definition at line 187 of file trajectory_planner_ros.h.
double base_local_planner::TrajectoryPlannerROS::rot_stopped_velocity_ [private] |
Definition at line 188 of file trajectory_planner_ros.h.
bool base_local_planner::TrajectoryPlannerROS::rotating_to_goal_ [private] |
Definition at line 200 of file trajectory_planner_ros.h.
double base_local_planner::TrajectoryPlannerROS::sim_period_ [private] |
Definition at line 199 of file trajectory_planner_ros.h.
The trajectory controller.
Definition at line 179 of file trajectory_planner_ros.h.
tf::TransformListener* base_local_planner::TrajectoryPlannerROS::tf_ [private] |
Used for transforming point clouds.
Definition at line 183 of file trajectory_planner_ros.h.
double base_local_planner::TrajectoryPlannerROS::trans_stopped_velocity_ [private] |
Definition at line 188 of file trajectory_planner_ros.h.
The world model that the controller will use.
Definition at line 178 of file trajectory_planner_ros.h.
double base_local_planner::TrajectoryPlannerROS::xy_goal_tolerance_ [private] |
Definition at line 189 of file trajectory_planner_ros.h.
Definition at line 201 of file trajectory_planner_ros.h.
double base_local_planner::TrajectoryPlannerROS::yaw_goal_tolerance_ [private] |
Definition at line 189 of file trajectory_planner_ros.h.