Go to the documentation of this file.
47 #include <nav_msgs/Path.h>
58 if (
setup_ && config.restore_defaults) {
60 config.restore_defaults =
false;
89 dp_->reconfigure(config);
93 odom_helper_(
"odom"), setup_(false) {
104 g_plan_pub_ = private_nh.advertise<nav_msgs::Path>(
"global_plan", 1);
105 l_plan_pub_ = private_nh.advertise<nav_msgs::Path>(
"local_plan", 1);
118 if( private_nh.getParam(
"odom_topic",
odom_topic_ ))
133 dsrv_ =
new dynamic_reconfigure::Server<DWAPlannerConfig>(private_nh);
134 dynamic_reconfigure::Server<DWAPlannerConfig>::CallbackType cb = [
this](
auto& config,
auto level){
reconfigureCB(config, level); };
135 dsrv_->setCallback(cb);
138 ROS_WARN(
"This planner has already been initialized, doing nothing.");
144 ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
151 return dp_->setPlan(orig_global_plan);
156 ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
191 ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
195 geometry_msgs::PoseStamped robot_vel;
205 geometry_msgs::PoseStamped drive_cmds;
221 cmd_vel.linear.x = drive_cmds.pose.position.x;
222 cmd_vel.linear.y = drive_cmds.pose.position.y;
226 std::vector<geometry_msgs::PoseStamped> local_plan;
229 "The dwa local planner failed to find a valid plan, cost functions discarded all candidates. This can mean there is an obstacle too close to the robot.");
235 ROS_DEBUG_NAMED(
"dwa_local_planner",
"A valid velocity command of (%.2f, %.2f, %.2f) was found for this cycle.",
236 cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z);
240 double p_x, p_y, p_th;
243 geometry_msgs::PoseStamped p;
246 p.pose.position.x = p_x;
247 p.pose.position.y = p_y;
248 p.pose.position.z = 0.0;
252 local_plan.push_back(p);
270 std::vector<geometry_msgs::PoseStamped> transformed_plan;
277 if(transformed_plan.empty()) {
278 ROS_WARN_NAMED(
"dwa_local_planner",
"Received an empty transformed plan.");
281 ROS_DEBUG_NAMED(
"dwa_local_planner",
"Received a transformed plan with %zu points.", transformed_plan.size());
288 std::vector<geometry_msgs::PoseStamped> local_plan;
289 std::vector<geometry_msgs::PoseStamped> transformed_plan;
300 [
this](
auto pos,
auto vel,
auto vel_samples){ return dp_->checkTrajectory(pos, vel, vel_samples); });
306 ROS_WARN_NAMED(
"dwa_local_planner",
"DWA planner failed to produce path.");
307 std::vector<geometry_msgs::PoseStamped> empty_plan;
void setOdomTopic(std::string odom_topic)
tf2_ros::Buffer * tf_
Used for transforming point clouds.
void convert(const A &a, B &b)
bool computeVelocityCommandsStopRotate(geometry_msgs::Twist &cmd_vel, Eigen::Vector3f acc_lim, double sim_period, LocalPlannerUtil *planner_util, OdometryHelperRos &odom_helper, const geometry_msgs::PoseStamped &global_pose, boost::function< bool(Eigen::Vector3f pos, Eigen::Vector3f vel, Eigen::Vector3f vel_samples)> obstacle_check)
base_local_planner::OdometryHelperRos odom_helper_
bool getLocalPlan(const geometry_msgs::PoseStamped &global_pose, std::vector< geometry_msgs::PoseStamped > &transformed_plan)
dwa_local_planner::DWAPlannerConfig default_config_
ros::Publisher l_plan_pub_
double getYaw(const A &a)
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
void reconfigureCB(DWAPlannerConfig &config, uint32_t level)
Callback to update the local planner's parameters based on dynamic reconfigure.
const std::string & getBaseFrameID() const noexcept
base_local_planner::LatchedStopRotateController latchedStopRotateController_
bool isPositionReached(LocalPlannerUtil *planner_util, const geometry_msgs::PoseStamped &global_pose)
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
void getRobotVel(geometry_msgs::PoseStamped &robot_vel)
A class implementing a local planner using the Dynamic Window Approach.
const std::vector< geometry_msgs::Point > & getRobotFootprint() const noexcept
void reconfigureCB(LocalPlannerLimits &config, bool restore_defaults)
~DWAPlannerROS()
Destructor for the wrapper.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_DEBUG_NAMED(name,...)
ROS Wrapper for the DWAPlanner that adheres to the BaseLocalPlanner interface and can be used as a pl...
Eigen::Vector3f getAccLimits()
void initialize(tf2_ros::Buffer *tf, costmap_2d::Costmap2D *costmap, std::string global_frame)
void warnRenamedParameter(const ros::NodeHandle &nh, const std::string current_name, const std::string old_name)
geometry_msgs::PoseStamped current_pose_
void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros)
Constructs the ros wrapper.
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
Set the plan that the controller is following.
bool isGoalReached(LocalPlannerUtil *planner_util, OdometryHelperRos &odom_helper, const geometry_msgs::PoseStamped &global_pose)
void publishLocalPlan(std::vector< geometry_msgs::PoseStamped > &path)
bool getRobotPose(geometry_msgs::PoseStamped &global_pose) const
ros::Publisher g_plan_pub_
void getPoint(unsigned int index, double &x, double &y, double &th) const
unsigned int getPointsSize() const
DWAPlannerROS()
Constructor for DWAPlannerROS wrapper.
void publishGlobalPlan(std::vector< geometry_msgs::PoseStamped > &path)
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...
#define ROS_WARN_NAMED(name,...)
LocalPlannerLimits getCurrentLimits()
Costmap2D * getCostmap() const
const std::string & getGlobalFrameID() const noexcept
boost::shared_ptr< DWAPlanner > dp_
The trajectory controller.
costmap_2d::Costmap2DROS * costmap_ros_
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub)
bool isGoalReached()
Check if the goal pose has been achieved.
double yaw_goal_tolerance
dynamic_reconfigure::Server< DWAPlannerConfig > * dsrv_
base_local_planner::LocalPlannerUtil planner_util_
dwa_local_planner
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:33