graceful_controller_ros.hpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2021-2022, Michael Ferguson
6  * Copyright (c) 2009, Willow Garage, Inc.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of Willow Garage, Inc. nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Author: Eitan Marder-Eppstein, Michael Ferguson
37  *********************************************************************/
38 
39 #ifndef GRACEFUL_CONTROLLER_ROS_GRACEFUL_CONTROLLER_ROS_HPP
40 #define GRACEFUL_CONTROLLER_ROS_GRACEFUL_CONTROLLER_ROS_HPP
41 
42 #include <mutex>
43 
45 #include <nav_msgs/Path.h>
46 
51 #include <std_msgs/Float32.h>
52 #include <tf2/utils.h>
54 
55 #include <dynamic_reconfigure/server.h>
56 #include <graceful_controller_ros/GracefulControllerConfig.h>
57 
59 
60 namespace graceful_controller
61 {
62 class GracefulControllerROS : public nav_core::BaseLocalPlanner
63 {
64 public:
66  virtual ~GracefulControllerROS();
67 
74  virtual void initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* costmap_ros);
75 
79  void reconfigureCallback(GracefulControllerConfig& config, uint32_t level);
80 
88  virtual bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel);
89 
94  virtual bool isGoalReached();
95 
101  virtual bool setPlan(const std::vector<geometry_msgs::PoseStamped>& plan);
102 
109  double rotateTowards(const geometry_msgs::PoseStamped& pose, geometry_msgs::Twist& cmd_vel);
110 
116  void rotateTowards(double yaw, geometry_msgs::Twist& cmd_vel);
117 
118 private:
119  void velocityCallback(const std_msgs::Float32::ConstPtr& max_vel_x);
120 
127  bool simulate(const geometry_msgs::PoseStamped& target_pose, geometry_msgs::Twist& cmd_vel);
128 
131 
132  bool initialized_;
134 
137  geometry_msgs::TransformStamped robot_to_costmap_transform_;
140 
141  // Parameters and dynamic reconfigure
142  std::mutex config_mutex_;
143  dynamic_reconfigure::Server<GracefulControllerConfig>* dsrv_;
144  double max_vel_x_;
145  double min_vel_x_;
146  double max_vel_theta_;
147  double max_vel_theta_limited_;
150  double acc_lim_x_;
151  double acc_lim_theta_;
152  double decel_lim_x_;
153  double scaling_vel_x_;
154  double scaling_factor_;
155  double scaling_step_;
156  double xy_goal_tolerance_;
157  double yaw_goal_tolerance_;
158  double xy_vel_goal_tolerance_;
160  double min_lookahead_;
161  double max_lookahead_;
162  double resolution_;
163  double acc_dt_;
164  double yaw_filter_tolerance_;
165  double yaw_gap_tolerance_;
169 
170  // Goal tolerance
172  bool goal_tolerance_met_;
173 
174  // Controls initial rotation towards path
176  bool has_new_path_;
177 
178  // Optional visualization of colliding and non-colliding points checked
180  visualization_msgs::MarkerArray* collision_points_;
181 
182  geometry_msgs::PoseStamped robot_pose_;
183 };
184 
191 void computeDistanceAlongPath(const std::vector<geometry_msgs::PoseStamped>& poses,
192  std::vector<double>& distances);
193 
194 } // namespace graceful_controller
195 
196 #endif // GRACEFUL_CONTROLLER_ROS_GRACEFUL_CONTROLLER_ROS_HPP
graceful_controller::GracefulControllerROS::planner_util_
base_local_planner::LocalPlannerUtil planner_util_
Definition: graceful_controller_ros.hpp:210
graceful_controller::GracefulControllerROS::resolution_
double resolution_
Definition: graceful_controller_ros.hpp:234
graceful_controller::GracefulControllerROS::GracefulControllerROS
GracefulControllerROS()
Definition: graceful_controller_ros.cpp:181
graceful_controller::GracefulControllerROS::yaw_vel_goal_tolerance_
double yaw_vel_goal_tolerance_
Definition: graceful_controller_ros.hpp:231
graceful_controller::GracefulControllerROS::compute_orientations_
bool compute_orientations_
Definition: graceful_controller_ros.hpp:239
ros::Publisher
graceful_controller::GracefulControllerROS::prefer_final_rotation_
bool prefer_final_rotation_
Definition: graceful_controller_ros.hpp:238
graceful_controller::GracefulControllerROS::max_lookahead_
double max_lookahead_
Definition: graceful_controller_ros.hpp:233
local_planner_util.h
graceful_controller::GracefulControllerROS::scaling_vel_x_
double scaling_vel_x_
Definition: graceful_controller_ros.hpp:225
graceful_controller::GracefulControllerROS::dsrv_
dynamic_reconfigure::Server< GracefulControllerConfig > * dsrv_
Definition: graceful_controller_ros.hpp:215
GracefulControllerPtr
std::shared_ptr< GracefulController > GracefulControllerPtr
graceful_controller::GracefulControllerROS::decel_lim_x_
double decel_lim_x_
Definition: graceful_controller_ros.hpp:224
graceful_controller::GracefulControllerROS::xy_goal_tolerance_
double xy_goal_tolerance_
Definition: graceful_controller_ros.hpp:228
visualization.hpp
graceful_controller::GracefulControllerROS::~GracefulControllerROS
virtual ~GracefulControllerROS()
Definition: graceful_controller_ros.cpp:185
graceful_controller::GracefulControllerROS::max_vel_x_
double max_vel_x_
Definition: graceful_controller_ros.hpp:216
graceful_controller::GracefulControllerROS::yaw_filter_tolerance_
double yaw_filter_tolerance_
Definition: graceful_controller_ros.hpp:236
utils.h
graceful_controller::GracefulControllerROS::max_x_to_max_theta_scale_factor_
double max_x_to_max_theta_scale_factor_
Definition: graceful_controller_ros.hpp:220
graceful_controller::GracefulControllerROS::goal_tolerance_met_
bool goal_tolerance_met_
Definition: graceful_controller_ros.hpp:244
base_local_planner::LocalPlannerUtil
graceful_controller::GracefulControllerROS::min_lookahead_
double min_lookahead_
Definition: graceful_controller_ros.hpp:232
graceful_controller::GracefulControllerROS::robot_pose_
geometry_msgs::PoseStamped robot_pose_
Definition: graceful_controller_ros.hpp:254
graceful_controller::GracefulControllerROS::min_vel_x_
double min_vel_x_
Definition: graceful_controller_ros.hpp:217
graceful_controller::GracefulControllerROS::has_new_path_
bool has_new_path_
Definition: graceful_controller_ros.hpp:248
graceful_controller::GracefulControllerROS::simulate
bool simulate(const geometry_msgs::PoseStamped &target_pose, geometry_msgs::Twist &cmd_vel)
Simulate a path.
Definition: graceful_controller_ros.cpp:539
graceful_controller
graceful_controller::GracefulControllerROS::max_vel_sub_
ros::Subscriber max_vel_sub_
Definition: graceful_controller_ros.hpp:202
graceful_controller::GracefulControllerROS::collision_points_
visualization_msgs::MarkerArray * collision_points_
Definition: graceful_controller_ros.hpp:252
graceful_controller::GracefulControllerROS::robot_to_costmap_transform_
geometry_msgs::TransformStamped robot_to_costmap_transform_
Definition: graceful_controller_ros.hpp:209
base_local_planner.h
graceful_controller::GracefulControllerROS::latch_xy_goal_tolerance_
bool latch_xy_goal_tolerance_
Definition: graceful_controller_ros.hpp:243
graceful_controller::GracefulControllerROS::rotateTowards
double rotateTowards(const geometry_msgs::PoseStamped &pose, geometry_msgs::Twist &cmd_vel)
Rotate the robot towards a goal.
Definition: graceful_controller_ros.cpp:777
graceful_controller::GracefulControllerROS::local_plan_pub_
ros::Publisher local_plan_pub_
Definition: graceful_controller_ros.hpp:201
graceful_controller::computeDistanceAlongPath
void computeDistanceAlongPath(const std::vector< geometry_msgs::PoseStamped > &poses, std::vector< double > &distances)
Compute distance of poses along a path. Assumes poses are in robot-centric frame.
Definition: graceful_controller_ros.cpp:834
orientation_tools.hpp
graceful_controller::GracefulControllerROS::controller_
GracefulControllerPtr controller_
Definition: graceful_controller_ros.hpp:205
graceful_controller::GracefulControllerROS::scaling_factor_
double scaling_factor_
Definition: graceful_controller_ros.hpp:226
base_local_planner::OdometryHelperRos
graceful_controller::GracefulControllerROS::scaling_step_
double scaling_step_
Definition: graceful_controller_ros.hpp:227
graceful_controller::GracefulControllerROS::acc_dt_
double acc_dt_
Definition: graceful_controller_ros.hpp:235
graceful_controller::GracefulControllerROS::velocityCallback
void velocityCallback(const std_msgs::Float32::ConstPtr &max_vel_x)
Definition: graceful_controller_ros.cpp:822
tf2_ros::Buffer
graceful_controller::GracefulControllerROS::initialized_
bool initialized_
Definition: graceful_controller_ros.hpp:204
graceful_controller::GracefulControllerROS::yaw_goal_tolerance_
double yaw_goal_tolerance_
Definition: graceful_controller_ros.hpp:229
graceful_controller::GracefulControllerROS::acc_lim_theta_
double acc_lim_theta_
Definition: graceful_controller_ros.hpp:223
graceful_controller.hpp
graceful_controller::GracefulControllerROS::computeVelocityCommands
virtual bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
Definition: graceful_controller_ros.cpp:327
graceful_controller::GracefulControllerROS::target_pose_pub_
ros::Publisher target_pose_pub_
Definition: graceful_controller_ros.hpp:201
graceful_controller::GracefulControllerROS::reconfigureCallback
void reconfigureCallback(GracefulControllerConfig &config, uint32_t level)
Callback for dynamic reconfigure server.
Definition: graceful_controller_ros.cpp:253
graceful_controller::GracefulControllerROS::max_vel_theta_
double max_vel_theta_
Definition: graceful_controller_ros.hpp:218
graceful_controller::GracefulControllerROS::setPlan
virtual bool setPlan(const std::vector< geometry_msgs::PoseStamped > &plan)
Set the plan that the local planner is following.
Definition: graceful_controller_ros.cpp:731
graceful_controller::GracefulControllerROS::global_plan_pub_
ros::Publisher global_plan_pub_
Definition: graceful_controller_ros.hpp:201
graceful_controller::GracefulControllerROS::yaw_gap_tolerance_
double yaw_gap_tolerance_
Definition: graceful_controller_ros.hpp:237
graceful_controller::GracefulControllerROS::use_orientation_filter_
bool use_orientation_filter_
Definition: graceful_controller_ros.hpp:240
graceful_controller::GracefulControllerROS::min_in_place_vel_theta_
double min_in_place_vel_theta_
Definition: graceful_controller_ros.hpp:221
tf2_geometry_msgs.h
graceful_controller::GracefulControllerROS::max_vel_theta_limited_
double max_vel_theta_limited_
Definition: graceful_controller_ros.hpp:219
tf
graceful_controller::GracefulControllerROS::buffer_
tf2_ros::Buffer * buffer_
Definition: graceful_controller_ros.hpp:207
graceful_controller::GracefulControllerROS::odom_helper_
base_local_planner::OdometryHelperRos odom_helper_
Definition: graceful_controller_ros.hpp:211
graceful_controller::GracefulControllerROS::isGoalReached
virtual bool isGoalReached()
Check if the goal pose has been achieved by the local planner.
Definition: graceful_controller_ros.cpp:680
graceful_controller::GracefulControllerROS::costmap_ros_
costmap_2d::Costmap2DROS * costmap_ros_
Definition: graceful_controller_ros.hpp:208
graceful_controller::GracefulControllerROS::acc_lim_x_
double acc_lim_x_
Definition: graceful_controller_ros.hpp:222
odometry_helper_ros.h
graceful_controller::GracefulControllerROS::config_mutex_
std::mutex config_mutex_
Definition: graceful_controller_ros.hpp:214
costmap_2d::Costmap2DROS
graceful_controller::GracefulControllerROS::initial_rotate_tolerance_
double initial_rotate_tolerance_
Definition: graceful_controller_ros.hpp:247
graceful_controller::GracefulControllerROS::initialize
virtual void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros)
Constructs the local planner.
Definition: graceful_controller_ros.cpp:197
graceful_controller::GracefulControllerROS::xy_vel_goal_tolerance_
double xy_vel_goal_tolerance_
Definition: graceful_controller_ros.hpp:230
nav_core::BaseLocalPlanner
graceful_controller::GracefulControllerROS::collision_point_pub_
ros::Publisher collision_point_pub_
Definition: graceful_controller_ros.hpp:251
ros::Subscriber


graceful_controller_ros
Author(s): Michael Ferguson
autogenerated on Wed Oct 23 2024 02:43:04