47 #include <nav_msgs/Path.h> 54 void DWAPlannerROS::reconfigureCB(DWAPlannerConfig &config, uint32_t level) {
55 if (setup_ && config.restore_defaults) {
56 config = default_config_;
57 config.restore_defaults =
false;
60 default_config_ = config;
86 dp_->reconfigure(config);
89 DWAPlannerROS::DWAPlannerROS() : initialized_(false),
90 odom_helper_(
"odom"), setup_(false) {
122 dsrv_ =
new dynamic_reconfigure::Server<DWAPlannerConfig>(private_nh);
124 dsrv_->setCallback(cb);
127 ROS_WARN(
"This planner has already been initialized, doing nothing.");
133 ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
140 return dp_->setPlan(orig_global_plan);
145 ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
180 ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
210 cmd_vel.linear.x = drive_cmds.getOrigin().getX();
211 cmd_vel.linear.y = drive_cmds.getOrigin().getY();
212 cmd_vel.angular.z =
tf::getYaw(drive_cmds.getRotation());
215 std::vector<geometry_msgs::PoseStamped> local_plan;
218 "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.");
224 ROS_DEBUG_NAMED(
"dwa_local_planner",
"A valid velocity command of (%.2f, %.2f, %.2f) was found for this cycle.",
225 cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z);
229 double p_x, p_y, p_th;
238 geometry_msgs::PoseStamped pose;
240 local_plan.push_back(pose);
258 std::vector<geometry_msgs::PoseStamped> transformed_plan;
265 if(transformed_plan.empty()) {
266 ROS_WARN_NAMED(
"dwa_local_planner",
"Received an empty transformed plan.");
269 ROS_DEBUG_NAMED(
"dwa_local_planner",
"Received a transformed plan with %zu points.", transformed_plan.size());
276 std::vector<geometry_msgs::PoseStamped> local_plan;
277 std::vector<geometry_msgs::PoseStamped> transformed_plan;
294 ROS_WARN_NAMED(
"dwa_local_planner",
"DWA planner failed to produce path.");
295 std::vector<geometry_msgs::PoseStamped> empty_plan;
boost::shared_ptr< DWAPlanner > dp_
The trajectory controller.
void reconfigureCB(DWAPlannerConfig &config, uint32_t level)
Callback to update the local planner's parameters based on dynamic reconfigure.
Eigen::Vector3f getAccLimits()
void getRobotVel(tf::Stamped< tf::Pose > &robot_vel)
bool getRobotPose(tf::Stamped< tf::Pose > &global_pose) const
#define ROS_WARN_NAMED(name,...)
dynamic_reconfigure::Server< DWAPlannerConfig > * dsrv_
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
void initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros)
Constructs the ros wrapper.
static double getYaw(const Quaternion &bt_q)
bool getLocalPlan(tf::Stamped< tf::Pose > &global_pose, std::vector< geometry_msgs::PoseStamped > &transformed_plan)
bool isGoalReached(LocalPlannerUtil *planner_util, OdometryHelperRos &odom_helper, tf::Stamped< tf::Pose > global_pose)
std::string getGlobalFrameID()
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
base_local_planner::OdometryHelperRos odom_helper_
void getPoint(unsigned int index, double &x, double &y, double &th) const
base_local_planner::LatchedStopRotateController latchedStopRotateController_
ROS Wrapper for the DWAPlanner that adheres to the BaseLocalPlanner interface and can be used as a pl...
void initialize(tf::TransformListener *tf, costmap_2d::Costmap2D *costmap, std::string global_frame)
#define ROS_DEBUG_NAMED(name,...)
bool dwaComputeVelocityCommands(tf::Stamped< tf::Pose > &global_pose, geometry_msgs::Twist &cmd_vel)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
bool computeVelocityCommandsStopRotate(geometry_msgs::Twist &cmd_vel, Eigen::Vector3f acc_lim, double sim_period, LocalPlannerUtil *planner_util, OdometryHelperRos &odom_helper, tf::Stamped< tf::Pose > global_pose, boost::function< bool(Eigen::Vector3f pos, Eigen::Vector3f vel, Eigen::Vector3f vel_samples)> obstacle_check)
tf::TransformListener * tf_
Used for transforming point clouds.
A class implementing a local planner using the Dynamic Window Approach.
costmap_2d::Costmap2DROS * costmap_ros_
static Quaternion createQuaternionFromYaw(double yaw)
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
LocalPlannerLimits getCurrentLimits()
std::string getBaseFrameID()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
Set the plan that the controller is following.
unsigned int getPointsSize() const
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub)
ros::Publisher l_plan_pub_
void publishLocalPlan(std::vector< geometry_msgs::PoseStamped > &path)
bool getParam(const std::string &key, std::string &s) const
void setOdomTopic(std::string odom_topic)
void publishGlobalPlan(std::vector< geometry_msgs::PoseStamped > &path)
~DWAPlannerROS()
Destructor for the wrapper.
std::vector< geometry_msgs::Point > getRobotFootprint()
bool isGoalReached()
Check if the goal pose has been achieved.
ros::Publisher g_plan_pub_
tf::Stamped< tf::Pose > current_pose_
base_local_planner::LocalPlannerUtil planner_util_
double yaw_goal_tolerance
bool checkTrajectory(const Eigen::Vector3f pos, const Eigen::Vector3f vel, const Eigen::Vector3f vel_samples)
Check if a trajectory is legal for a position/velocity pair.
bool isPositionReached(LocalPlannerUtil *planner_util, tf::Stamped< tf::Pose > global_pose)