dwa_planner_ros.h
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2009, 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 Willow Garage, Inc. 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 DWA_LOCAL_PLANNER_DWA_PLANNER_ROS_H_
38 #define DWA_LOCAL_PLANNER_DWA_PLANNER_ROS_H_
39 
40 #include <boost/shared_ptr.hpp>
41 #include <boost/thread.hpp>
42 
43 #include <tf2_ros/buffer.h>
44 
45 #include <dynamic_reconfigure/server.h>
46 #include <dwa_local_planner/DWAPlannerConfig.h>
47 
48 #include <angles/angles.h>
49 
50 #include <nav_msgs/Odometry.h>
51 
55 
57 
59 
60 namespace dwa_local_planner {
66  class DWAPlannerROS : public nav_core::BaseLocalPlanner {
67  public:
71  DWAPlannerROS();
72 
79  void initialize(std::string name, tf2_ros::Buffer* tf,
80  costmap_2d::Costmap2DROS* costmap_ros);
81 
86 
93  bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel);
94 
95 
102  bool dwaComputeVelocityCommands(geometry_msgs::PoseStamped& global_pose, geometry_msgs::Twist& cmd_vel);
103 
109  bool setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan);
110 
115  bool isGoalReached();
116 
117 
118 
119  bool isInitialized() {
120  return initialized_;
121  }
122 
123  private:
127  void reconfigureCB(DWAPlannerConfig &config, uint32_t level);
128 
129  void publishLocalPlan(std::vector<geometry_msgs::PoseStamped>& path);
130 
131  void publishGlobalPlan(std::vector<geometry_msgs::PoseStamped>& path);
132 
134 
135  // for visualisation, publishers of global and local plan
137 
139 
141 
143 
144  dynamic_reconfigure::Server<DWAPlannerConfig> *dsrv_;
145  dwa_local_planner::DWAPlannerConfig default_config_;
146  bool setup_;
147  geometry_msgs::PoseStamped current_pose_;
148 
150 
151 
152  bool initialized_;
153 
154 
156  std::string odom_topic_;
157  };
158 };
159 #endif
dwa_local_planner::DWAPlannerROS::tf_
tf2_ros::Buffer * tf_
Used for transforming point clouds.
Definition: dwa_planner_ros.h:168
dwa_local_planner::DWAPlannerROS::initialized_
bool initialized_
Definition: dwa_planner_ros.h:187
ros::Publisher
dwa_local_planner::DWAPlannerROS::odom_helper_
base_local_planner::OdometryHelperRos odom_helper_
Definition: dwa_planner_ros.h:190
dwa_local_planner::DWAPlannerROS::default_config_
dwa_local_planner::DWAPlannerConfig default_config_
Definition: dwa_planner_ros.h:180
dwa_local_planner::DWAPlannerROS::l_plan_pub_
ros::Publisher l_plan_pub_
Definition: dwa_planner_ros.h:171
boost::shared_ptr
base_local_planner::LocalPlannerUtil
latched_stop_rotate_controller.h
dwa_local_planner::DWAPlannerROS::reconfigureCB
void reconfigureCB(DWAPlannerConfig &config, uint32_t level)
Callback to update the local planner's parameters based on dynamic reconfigure.
Definition: dwa_planner_ros.cpp:92
buffer.h
dwa_local_planner::DWAPlannerROS::latchedStopRotateController_
base_local_planner::LatchedStopRotateController latchedStopRotateController_
Definition: dwa_planner_ros.h:184
costmap_2d_ros.h
dwa_local_planner::DWAPlannerROS::computeVelocityCommands
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
Definition: dwa_planner_ros.cpp:299
dwa_local_planner::DWAPlannerROS::isInitialized
bool isInitialized()
Definition: dwa_planner_ros.h:154
dwa_planner.h
base_local_planner.h
dwa_local_planner::DWAPlannerROS::~DWAPlannerROS
~DWAPlannerROS()
Destructor for the wrapper.
Definition: dwa_planner_ros.cpp:216
base_local_planner::OdometryHelperRos
tf2_ros::Buffer
dwa_local_planner::DWAPlannerROS::odom_topic_
std::string odom_topic_
Definition: dwa_planner_ros.h:191
base_local_planner::LatchedStopRotateController
dwa_local_planner::DWAPlannerROS::current_pose_
geometry_msgs::PoseStamped current_pose_
Definition: dwa_planner_ros.h:182
dwa_local_planner::DWAPlannerROS::initialize
void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros)
Constructs the ros wrapper.
Definition: dwa_planner_ros.cpp:132
dwa_local_planner::DWAPlannerROS::setPlan
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
Set the plan that the controller is following.
Definition: dwa_planner_ros.cpp:177
dwa_local_planner::DWAPlannerROS::publishLocalPlan
void publishLocalPlan(std::vector< geometry_msgs::PoseStamped > &path)
Definition: dwa_planner_ros.cpp:207
dwa_local_planner::DWAPlannerROS::setup_
bool setup_
Definition: dwa_planner_ros.h:181
dwa_local_planner::DWAPlannerROS::g_plan_pub_
ros::Publisher g_plan_pub_
Definition: dwa_planner_ros.h:171
dwa_local_planner
Definition: dwa_planner.h:65
dwa_local_planner::DWAPlannerROS::DWAPlannerROS
DWAPlannerROS()
Constructor for DWAPlannerROS wrapper.
Definition: dwa_planner_ros.cpp:127
dwa_local_planner::DWAPlannerROS::publishGlobalPlan
void publishGlobalPlan(std::vector< geometry_msgs::PoseStamped > &path)
Definition: dwa_planner_ros.cpp:212
dwa_local_planner::DWAPlannerROS::dwaComputeVelocityCommands
bool dwaComputeVelocityCommands(geometry_msgs::PoseStamped &global_pose, geometry_msgs::Twist &cmd_vel)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
Definition: dwa_planner_ros.cpp:223
tf
dwa_local_planner::DWAPlannerROS::dp_
boost::shared_ptr< DWAPlanner > dp_
The trajectory controller.
Definition: dwa_planner_ros.h:175
dwa_local_planner::DWAPlannerROS::costmap_ros_
costmap_2d::Costmap2DROS * costmap_ros_
Definition: dwa_planner_ros.h:177
dwa_local_planner::DWAPlannerROS::isGoalReached
bool isGoalReached()
Check if the goal pose has been achieved.
Definition: dwa_planner_ros.cpp:189
odometry_helper_ros.h
costmap_2d::Costmap2DROS
nav_core::BaseLocalPlanner
angles.h
dwa_local_planner::DWAPlannerROS::dsrv_
dynamic_reconfigure::Server< DWAPlannerConfig > * dsrv_
Definition: dwa_planner_ros.h:179
dwa_local_planner::DWAPlannerROS::planner_util_
base_local_planner::LocalPlannerUtil planner_util_
Definition: dwa_planner_ros.h:173


dwa_local_planner
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:33