trajectory_planner_ros.h
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2008, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of the Willow Garage nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Eitan Marder-Eppstein
36 *********************************************************************/
37 #ifndef TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_ROS_H_
38 #define TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_ROS_H_
39 
40 #include <ros/ros.h>
41 #include <costmap_2d/costmap_2d.h>
50 
52 
53 #include <nav_msgs/Odometry.h>
54 #include <geometry_msgs/PoseStamped.h>
55 #include <geometry_msgs/Twist.h>
56 #include <geometry_msgs/Point.h>
57 
58 #include <tf2_ros/buffer.h>
59 
60 #include <boost/thread.hpp>
61 
62 #include <string>
63 
64 #include <angles/angles.h>
65 
67 
68 #include <dynamic_reconfigure/server.h>
69 #include <base_local_planner/BaseLocalPlannerConfig.h>
70 
72 
73 namespace base_local_planner {
79  public:
84 
91  TrajectoryPlannerROS(std::string name,
93  costmap_2d::Costmap2DROS* costmap_ros);
94 
101  void initialize(std::string name, tf2_ros::Buffer* tf,
102  costmap_2d::Costmap2DROS* costmap_ros);
103 
108 
115  bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel);
116 
122  bool setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan);
123 
128  bool isGoalReached();
129 
141  bool checkTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map = true);
142 
154  double scoreTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map = true);
155 
156  bool isInitialized() {
157  return initialized_;
158  }
159 
161  TrajectoryPlanner* getPlanner() const { return tc_; }
162 
163  private:
167  void reconfigureCB(BaseLocalPlannerConfig &config, uint32_t level);
168 
177  bool rotateToGoal(const geometry_msgs::PoseStamped& global_pose, const geometry_msgs::PoseStamped& robot_vel, double goal_th, geometry_msgs::Twist& cmd_vel);
178 
186  bool stopWithAccLimits(const geometry_msgs::PoseStamped& global_pose, const geometry_msgs::PoseStamped& robot_vel, geometry_msgs::Twist& cmd_vel);
187 
188  std::vector<double> loadYVels(ros::NodeHandle node);
189 
190  double sign(double x){
191  return x < 0.0 ? -1.0 : 1.0;
192  }
193 
196 
201  std::string global_frame_;
203  nav_msgs::Odometry base_odom_;
204  std::string robot_base_frame_;
207  std::vector<geometry_msgs::PoseStamped> global_plan_;
209  boost::recursive_mutex odom_lock_;
210 
213  double sim_period_;
217 
219 
220  dynamic_reconfigure::Server<BaseLocalPlannerConfig> *dsrv_;
221  base_local_planner::BaseLocalPlannerConfig default_config_;
222  bool setup_;
223 
224 
227 
228  std::vector<geometry_msgs::Point> footprint_spec_;
229  };
230 };
231 #endif
Computes control velocities for a robot given a costmap, a plan, and the robot&#39;s position in the worl...
nav_msgs::Odometry base_odom_
Used to get the velocity of the robot.
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...
dynamic_reconfigure::Server< BaseLocalPlannerConfig > * dsrv_
costmap_2d::Costmap2D * costmap_
The costmap the controller will use.
std::string global_frame_
The frame in which the controller will run.
base_local_planner::BaseLocalPlannerConfig default_config_
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.
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.
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...
Definition: world_model.h:52
base_local_planner::OdometryHelperRos odom_helper_
void reconfigureCB(BaseLocalPlannerConfig &config, uint32_t level)
Callback to update the local planner&#39;s parameters based on dynamic reconfigure.
WorldModel * world_model_
The world model that the controller will use.
TrajectoryPlanner * getPlanner() const
Return the inner TrajectoryPlanner object. Only valid after initialize().
void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros)
Constructs the ros wrapper.
std::vector< geometry_msgs::PoseStamped > global_plan_
TrajectoryPlannerROS()
Default constructor for the ros wrapper.
~TrajectoryPlannerROS()
Destructor for the wrapper.
A ROS wrapper for the trajectory controller that queries the param server to construct a controller...
tf2_ros::Buffer * tf_
Used for transforming point clouds.
costmap_2d::Costmap2DROS * costmap_ros_
The ROS wrapper for the costmap the controller will use.
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.


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Wed Jun 22 2022 02:07:08