37 #ifndef TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_ROS_H_ 38 #define TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_ROS_H_ 55 #include <nav_msgs/Odometry.h> 56 #include <geometry_msgs/PoseStamped.h> 57 #include <geometry_msgs/Twist.h> 58 #include <geometry_msgs/Point.h> 62 #include <boost/thread.hpp> 70 #include <dynamic_reconfigure/server.h> 71 #include <base_local_planner/BaseLocalPlannerConfig.h> 124 bool setPlan(
const std::vector<geometry_msgs::PoseStamped>& orig_global_plan);
143 bool checkTrajectory(
double vx_samp,
double vy_samp,
double vtheta_samp,
bool update_map =
true);
156 double scoreTrajectory(
double vx_samp,
double vy_samp,
double vtheta_samp,
bool update_map =
true);
169 void reconfigureCB(BaseLocalPlannerConfig &config, uint32_t level);
193 return x < 0.0 ? -1.0 : 1.0;
222 dynamic_reconfigure::Server<BaseLocalPlannerConfig> *
dsrv_;
Computes control velocities for a robot given a costmap, a plan, and the robot's position in the worl...
void initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros)
Constructs the ros wrapper.
nav_msgs::Odometry base_odom_
Used to get the velocity of the robot.
TrajectoryPlanner * getPlanner() const
Return the inner TrajectoryPlanner object. Only valid after initialize().
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
Set the plan that the controller is following.
std::string robot_base_frame_
Used as the base frame id of the robot.
std::vector< double > loadYVels(ros::NodeHandle node)
bool isGoalReached()
Check if the goal pose has been achieved.
std::vector< geometry_msgs::Point > footprint_spec_
double max_sensor_range_
Keep track of the effective maximum range of our sensors.
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
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.
ros::Publisher g_plan_pub_
boost::recursive_mutex odom_lock_
dynamic_reconfigure::Server< BaseLocalPlannerConfig > * dsrv_
costmap_2d::Costmap2D * costmap_
The costmap the controller will use.
double rot_stopped_velocity_
bool latch_xy_goal_tolerance_
double yaw_goal_tolerance_
std::string global_frame_
The frame in which the controller will run.
base_local_planner::BaseLocalPlannerConfig default_config_
double xy_goal_tolerance_
double scoreTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map=true)
Generate and score a single trajectory.
MapGridVisualizer map_viz_
The map grid visualizer for outputting the potential field generated by the cost function.
TrajectoryPlanner * tc_
The trajectory controller.
double trans_stopped_velocity_
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.
bool checkTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map=true)
Generate and score a single trajectory.
An interface the trajectory controller uses to interact with the world regardless of the underlying w...
base_local_planner::OdometryHelperRos odom_helper_
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::vector< geometry_msgs::PoseStamped > global_plan_
TrajectoryPlannerROS()
Default constructor for the ros wrapper.
tf::TransformListener * tf_
Used for transforming point clouds.
~TrajectoryPlannerROS()
Destructor for the wrapper.
A ROS wrapper for the trajectory controller that queries the param server to construct a controller...
costmap_2d::Costmap2DROS * costmap_ros_
The ROS wrapper for the costmap the controller will use.
ros::Publisher l_plan_pub_
double min_in_place_vel_th_