Go to the documentation of this file.
37 #ifndef TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_ROS_H_
38 #define TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_ROS_H_
53 #include <nav_msgs/Odometry.h>
54 #include <geometry_msgs/PoseStamped.h>
55 #include <geometry_msgs/Twist.h>
56 #include <geometry_msgs/Point.h>
60 #include <boost/thread.hpp>
68 #include <dynamic_reconfigure/server.h>
69 #include <base_local_planner/BaseLocalPlannerConfig.h>
122 bool setPlan(
const std::vector<geometry_msgs::PoseStamped>& orig_global_plan);
141 bool checkTrajectory(
double vx_samp,
double vy_samp,
double vtheta_samp,
bool update_map =
true);
154 double scoreTrajectory(
double vx_samp,
double vy_samp,
double vtheta_samp,
bool update_map =
true);
167 void reconfigureCB(BaseLocalPlannerConfig &config, uint32_t level);
177 bool rotateToGoal(
const geometry_msgs::PoseStamped& global_pose,
const geometry_msgs::PoseStamped& robot_vel,
double goal_th, geometry_msgs::Twist& cmd_vel);
186 bool stopWithAccLimits(
const geometry_msgs::PoseStamped& global_pose,
const geometry_msgs::PoseStamped& robot_vel, geometry_msgs::Twist& cmd_vel);
190 double sign(
double x){
191 return x < 0.0 ? -1.0 : 1.0;
220 dynamic_reconfigure::Server<BaseLocalPlannerConfig> *
dsrv_;
TrajectoryPlanner * getPlanner() const
Return the inner TrajectoryPlanner object. Only valid after initialize().
base_local_planner::BaseLocalPlannerConfig default_config_
TrajectoryPlanner * tc_
The trajectory controller.
bool checkTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map=true)
Generate and score a single trajectory.
ros::Publisher l_plan_pub_
nav_msgs::Odometry base_odom_
Used to get the velocity of the robot.
base_local_planner::OdometryHelperRos odom_helper_
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
double scoreTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map=true)
Generate and score a single trajectory.
~TrajectoryPlannerROS()
Destructor for the wrapper.
double min_in_place_vel_th_
void reconfigureCB(BaseLocalPlannerConfig &config, uint32_t level)
Callback to update the local planner's parameters based on dynamic reconfigure.
WorldModel * world_model_
The world model that the controller will use.
std::string global_frame_
The frame in which the controller will run.
void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros)
Constructs the ros wrapper.
boost::recursive_mutex odom_lock_
double rot_stopped_velocity_
costmap_2d::Costmap2DROS * costmap_ros_
The ROS wrapper for the costmap the controller will use.
bool latch_xy_goal_tolerance_
std::vector< geometry_msgs::Point > footprint_spec_
std::string robot_base_frame_
Used as the base frame id of the robot.
costmap_2d::Costmap2D * costmap_
The costmap the controller will use.
double xy_goal_tolerance_
An interface the trajectory controller uses to interact with the world regardless of the underlying w...
std::vector< geometry_msgs::PoseStamped > global_plan_
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
Set the plan that the controller is following.
bool isGoalReached()
Check if the goal pose has been achieved.
std::vector< double > loadYVels(ros::NodeHandle node)
Computes control velocities for a robot given a costmap, a plan, and the robot's position in the worl...
double max_sensor_range_
Keep track of the effective maximum range of our sensors.
dynamic_reconfigure::Server< BaseLocalPlannerConfig > * dsrv_
MapGridVisualizer map_viz_
The map grid visualizer for outputting the potential field generated by the cost function.
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.
tf2_ros::Buffer * tf_
Used for transforming point clouds.
TrajectoryPlannerROS()
Default constructor for the ros wrapper.
ros::Publisher g_plan_pub_
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.
double yaw_goal_tolerance_
double trans_stopped_velocity_
base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:24