A ROS wrapper for the trajectory controller that queries the param server to construct a controller.
More...
#include <trajectory_planner_ros.h>
|
bool | checkTrajectory (double vx_samp, double vy_samp, double vtheta_samp, bool update_map=true) |
| Generate and score a single trajectory. More...
|
|
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. More...
|
|
TrajectoryPlanner * | getPlanner () const |
| Return the inner TrajectoryPlanner object. Only valid after initialize(). More...
|
|
void | initialize (std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros) |
| Constructs the ros wrapper. More...
|
|
bool | isGoalReached () |
| Check if the goal pose has been achieved. More...
|
|
bool | isInitialized () |
|
double | scoreTrajectory (double vx_samp, double vy_samp, double vtheta_samp, bool update_map=true) |
| Generate and score a single trajectory. More...
|
|
bool | setPlan (const std::vector< geometry_msgs::PoseStamped > &orig_global_plan) |
| Set the plan that the controller is following. More...
|
|
| TrajectoryPlannerROS () |
| Default constructor for the ros wrapper. More...
|
|
| TrajectoryPlannerROS (std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros) |
| Constructs the ros wrapper. More...
|
|
| ~TrajectoryPlannerROS () |
| Destructor for the wrapper. More...
|
|
virtual | ~BaseLocalPlanner () |
|
|
std::vector< double > | loadYVels (ros::NodeHandle node) |
|
void | reconfigureCB (BaseLocalPlannerConfig &config, uint32_t level) |
| Callback to update the local planner's parameters based on dynamic reconfigure. More...
|
|
bool | rotateToGoal (const geometry_msgs::PoseStamped &global_pose, const geometry_msgs::PoseStamped &robot_vel, double goal_th, geometry_msgs::Twist &cmd_vel) |
| Once a goal position is reached... rotate to the goal orientation. More...
|
|
double | sign (double x) |
|
bool | stopWithAccLimits (const geometry_msgs::PoseStamped &global_pose, const geometry_msgs::PoseStamped &robot_vel, geometry_msgs::Twist &cmd_vel) |
| Stop the robot taking into account acceleration limits. More...
|
|
A ROS wrapper for the trajectory controller that queries the param server to construct a controller.
Definition at line 113 of file trajectory_planner_ros.h.
◆ TrajectoryPlannerROS() [1/2]
base_local_planner::TrajectoryPlannerROS::TrajectoryPlannerROS |
( |
| ) |
|
◆ TrajectoryPlannerROS() [2/2]
Constructs the ros wrapper.
- Parameters
-
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 116 of file trajectory_planner_ros.cpp.
◆ ~TrajectoryPlannerROS()
base_local_planner::TrajectoryPlannerROS::~TrajectoryPlannerROS |
( |
| ) |
|
◆ checkTrajectory()
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.
- Parameters
-
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 |
- Returns
- True if the trajectory is legal, false otherwise
Definition at line 590 of file trajectory_planner_ros.cpp.
◆ computeVelocityCommands()
bool base_local_planner::TrajectoryPlannerROS::computeVelocityCommands |
( |
geometry_msgs::Twist & |
cmd_vel | ) |
|
|
virtual |
Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base.
- Parameters
-
cmd_vel | Will be filled with the velocity command to be passed to the robot base |
- Returns
- True if a valid trajectory was found, false otherwise
Implements nav_core::BaseLocalPlanner.
Definition at line 434 of file trajectory_planner_ros.cpp.
◆ getPlanner()
◆ initialize()
Constructs the ros wrapper.
- Parameters
-
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 |
Implements nav_core::BaseLocalPlanner.
Definition at line 123 of file trajectory_planner_ros.cpp.
◆ isGoalReached()
bool base_local_planner::TrajectoryPlannerROS::isGoalReached |
( |
| ) |
|
|
virtual |
◆ isInitialized()
bool base_local_planner::TrajectoryPlannerROS::isInitialized |
( |
| ) |
|
|
inline |
◆ loadYVels()
std::vector< double > base_local_planner::TrajectoryPlannerROS::loadYVels |
( |
ros::NodeHandle |
node | ) |
|
|
private |
◆ reconfigureCB()
void base_local_planner::TrajectoryPlannerROS::reconfigureCB |
( |
BaseLocalPlannerConfig & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
private |
◆ rotateToGoal()
bool base_local_planner::TrajectoryPlannerROS::rotateToGoal |
( |
const geometry_msgs::PoseStamped & |
global_pose, |
|
|
const geometry_msgs::PoseStamped & |
robot_vel, |
|
|
double |
goal_th, |
|
|
geometry_msgs::Twist & |
cmd_vel |
|
) |
| |
|
private |
Once a goal position is reached... rotate to the goal orientation.
- Parameters
-
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 |
- Returns
- True if a valid trajectory was found, false otherwise
Definition at line 374 of file trajectory_planner_ros.cpp.
◆ scoreTrajectory()
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.
- Parameters
-
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 |
- Returns
- score of trajectory (double)
Definition at line 619 of file trajectory_planner_ros.cpp.
◆ setPlan()
bool base_local_planner::TrajectoryPlannerROS::setPlan |
( |
const std::vector< geometry_msgs::PoseStamped > & |
orig_global_plan | ) |
|
|
virtual |
◆ sign()
double base_local_planner::TrajectoryPlannerROS::sign |
( |
double |
x | ) |
|
|
inlineprivate |
◆ stopWithAccLimits()
bool base_local_planner::TrajectoryPlannerROS::stopWithAccLimits |
( |
const geometry_msgs::PoseStamped & |
global_pose, |
|
|
const geometry_msgs::PoseStamped & |
robot_vel, |
|
|
geometry_msgs::Twist & |
cmd_vel |
|
) |
| |
|
private |
Stop the robot taking into account acceleration limits.
- Parameters
-
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 |
- Returns
- True if a valid trajectory was found, false otherwise
Definition at line 345 of file trajectory_planner_ros.cpp.
◆ acc_lim_theta_
double base_local_planner::TrajectoryPlannerROS::acc_lim_theta_ |
|
private |
◆ acc_lim_x_
double base_local_planner::TrajectoryPlannerROS::acc_lim_x_ |
|
private |
◆ acc_lim_y_
double base_local_planner::TrajectoryPlannerROS::acc_lim_y_ |
|
private |
◆ base_odom_
nav_msgs::Odometry base_local_planner::TrajectoryPlannerROS::base_odom_ |
|
private |
◆ costmap_
◆ costmap_ros_
◆ default_config_
base_local_planner::BaseLocalPlannerConfig base_local_planner::TrajectoryPlannerROS::default_config_ |
|
private |
◆ dsrv_
dynamic_reconfigure::Server<BaseLocalPlannerConfig>* base_local_planner::TrajectoryPlannerROS::dsrv_ |
|
private |
◆ footprint_spec_
◆ g_plan_pub_
◆ global_frame_
std::string base_local_planner::TrajectoryPlannerROS::global_frame_ |
|
private |
◆ global_plan_
std::vector<geometry_msgs::PoseStamped> base_local_planner::TrajectoryPlannerROS::global_plan_ |
|
private |
◆ initialized_
bool base_local_planner::TrajectoryPlannerROS::initialized_ |
|
private |
◆ l_plan_pub_
◆ latch_xy_goal_tolerance_
bool base_local_planner::TrajectoryPlannerROS::latch_xy_goal_tolerance_ |
|
private |
◆ map_viz_
The map grid visualizer for outputting the potential field generated by the cost function.
Definition at line 234 of file trajectory_planner_ros.h.
◆ max_sensor_range_
double base_local_planner::TrajectoryPlannerROS::max_sensor_range_ |
|
private |
◆ max_vel_th_
double base_local_planner::TrajectoryPlannerROS::max_vel_th_ |
|
private |
◆ min_in_place_vel_th_
double base_local_planner::TrajectoryPlannerROS::min_in_place_vel_th_ |
|
private |
◆ min_vel_th_
double base_local_planner::TrajectoryPlannerROS::min_vel_th_ |
|
private |
◆ odom_helper_
◆ odom_lock_
boost::recursive_mutex base_local_planner::TrajectoryPlannerROS::odom_lock_ |
|
private |
◆ prune_plan_
bool base_local_planner::TrajectoryPlannerROS::prune_plan_ |
|
private |
◆ reached_goal_
bool base_local_planner::TrajectoryPlannerROS::reached_goal_ |
|
private |
◆ robot_base_frame_
std::string base_local_planner::TrajectoryPlannerROS::robot_base_frame_ |
|
private |
◆ rot_stopped_velocity_
double base_local_planner::TrajectoryPlannerROS::rot_stopped_velocity_ |
|
private |
◆ rotating_to_goal_
bool base_local_planner::TrajectoryPlannerROS::rotating_to_goal_ |
|
private |
◆ setup_
bool base_local_planner::TrajectoryPlannerROS::setup_ |
|
private |
◆ sim_period_
double base_local_planner::TrajectoryPlannerROS::sim_period_ |
|
private |
◆ tc_
◆ tf_
◆ trans_stopped_velocity_
double base_local_planner::TrajectoryPlannerROS::trans_stopped_velocity_ |
|
private |
◆ world_model_
WorldModel* base_local_planner::TrajectoryPlannerROS::world_model_ |
|
private |
◆ xy_goal_tolerance_
double base_local_planner::TrajectoryPlannerROS::xy_goal_tolerance_ |
|
private |
◆ xy_tolerance_latch_
bool base_local_planner::TrajectoryPlannerROS::xy_tolerance_latch_ |
|
private |
◆ yaw_goal_tolerance_
double base_local_planner::TrajectoryPlannerROS::yaw_goal_tolerance_ |
|
private |
The documentation for this class was generated from the following files: