Skip to content

Commit

Permalink
Address PR comments
Browse files Browse the repository at this point in the history
  • Loading branch information
shivaang12 committed Feb 10, 2020
1 parent 966e1b9 commit 0ada5a4
Show file tree
Hide file tree
Showing 29 changed files with 265 additions and 158 deletions.
4 changes: 4 additions & 0 deletions nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -112,6 +112,10 @@ controller_server:
FollowPath.PathDist.scale: 3.0
FollowPath.GoalDist.scale: 4.0
FollowPath.RotateToGoal.scale: 2.0
FollowPath.short_circuit_trajectory_evaluation: True
FollowPath.trans_stopped_velocity: 0.25
FollowPath.slowing_factor: 5.0
FollowPath.lookahead_time: -1.0

controller_server_rclcpp_node:
ros__parameters:
Expand Down
4 changes: 4 additions & 0 deletions nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -112,6 +112,10 @@ controller_server:
FollowPath.PathDist.scale: 3.0
FollowPath.GoalDist.scale: 4.0
FollowPath.RotateToGoal.scale: 2.0
FollowPath.short_circuit_trajectory_evaluation: True
FollowPath.trans_stopped_velocity: 0.25
FollowPath.slowing_factor: 5.0
FollowPath.lookahead_time: -1.0

controller_server_rclcpp_node:
ros__parameters:
Expand Down
4 changes: 4 additions & 0 deletions nav2_bringup/bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,10 @@ controller_server:
FollowPath.PathDist.scale: 3.0
FollowPath.GoalDist.scale: 4.0
FollowPath.RotateToGoal.scale: 2.0
FollowPath.short_circuit_trajectory_evaluation: True
FollowPath.trans_stopped_velocity: 0.25
FollowPath.slowing_factor: 5.0
FollowPath.lookahead_time: -1.0

controller_server_rclcpp_node:
ros__parameters:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -175,7 +175,8 @@ class DWBLocalPlanner : public nav2_core::Controller
* and the saved global_plan_. Technically, it iterates to a pose on the path that is within prune_distance_
* of the robot and erases all poses before that.
*/
virtual nav_2d_msgs::msg::Path2D transformGlobalPlan(const nav_2d_msgs::msg::Pose2DStamped & pose);
virtual nav_2d_msgs::msg::Path2D transformGlobalPlan(
const nav_2d_msgs::msg::Pose2DStamped & pose);
nav_2d_msgs::msg::Path2D global_plan_; ///< Saved Global Plan
bool prune_plan_;
double prune_distance_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,8 @@ class TrajectoryCritic
nh_ = nh;
dwb_plugin_name_ = ns;
if (!nh_->has_parameter(dwb_plugin_name_ + "." + name_ + ".scale")) {
nh_->declare_parameter(dwb_plugin_name_ + "." + name_ + ".scale",
nh_->declare_parameter(
dwb_plugin_name_ + "." + name_ + ".scale",
rclcpp::ParameterValue(1.0));
}
nh_->get_parameter(dwb_plugin_name_ + "." + name_ + ".scale", scale_);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,9 @@ namespace dwb_local_planner
* Linearly searches through the poses. Once the poses time_offset is greater than the desired time_offset,
* the search ends, since the poses have increasing time_offsets.
*/
const geometry_msgs::msg::Pose2D& getClosestPose(const dwb_msgs::msg::Trajectory2D& trajectory, const double time_offset);
const geometry_msgs::msg::Pose2D & getClosestPose(
const dwb_msgs::msg::Trajectory2D & trajectory,
const double time_offset);

/**
* @brief Helper function to create a pose with an exact time_offset by linearly interpolating between existing poses
Expand All @@ -58,8 +60,10 @@ const geometry_msgs::msg::Pose2D& getClosestPose(const dwb_msgs::msg::Trajectory
* @return New Pose2D with interpolated values
* @note If the given time offset is outside the bounds of the trajectory, the return pose will be either the first or last pose.
*/
geometry_msgs::msg::Pose2D projectPose(const dwb_msgs::msg::Trajectory2D& trajectory, const double time_offset);
geometry_msgs::msg::Pose2D projectPose(
const dwb_msgs::msg::Trajectory2D & trajectory,
const double time_offset);

} // namespace dwb_local_planner

#endif // DWB_LOCAL_PLANNER_TRAJECTORY_UTILS_H
#endif // DWB_LOCAL_PLANNER_TRAJECTORY_UTILS_H
65 changes: 43 additions & 22 deletions nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,19 +74,26 @@ void DWBLocalPlanner::configure(
tf_ = tf;
dwb_plugin_name_ = name;
declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".critics");
declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".prune_plan",
declare_parameter_if_not_declared(
node_, dwb_plugin_name_ + ".prune_plan",
rclcpp::ParameterValue(true));
declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".prune_distance",
declare_parameter_if_not_declared(
node_, dwb_plugin_name_ + ".prune_distance",
rclcpp::ParameterValue(1.0));
declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".debug_trajectory_details",
declare_parameter_if_not_declared(
node_, dwb_plugin_name_ + ".debug_trajectory_details",
rclcpp::ParameterValue(false));
declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".trajectory_generator_name",
declare_parameter_if_not_declared(
node_, dwb_plugin_name_ + ".trajectory_generator_name",
rclcpp::ParameterValue(std::string("dwb_plugins::StandardTrajectoryGenerator")));
declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".goal_checker_name",
declare_parameter_if_not_declared(
node_, dwb_plugin_name_ + ".goal_checker_name",
rclcpp::ParameterValue(std::string("dwb_plugins::SimpleGoalChecker")));
declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".transform_tolerance",
declare_parameter_if_not_declared(
node_, dwb_plugin_name_ + ".transform_tolerance",
rclcpp::ParameterValue(0.1));
declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".short_circuit_trajectory_evaluation",
declare_parameter_if_not_declared(
node_, dwb_plugin_name_ + ".short_circuit_trajectory_evaluation",
rclcpp::ParameterValue(true));

std::string traj_generator_name;
Expand All @@ -102,7 +109,9 @@ void DWBLocalPlanner::configure(
node_->get_parameter(dwb_plugin_name_ + ".debug_trajectory_details", debug_trajectory_details_);
node_->get_parameter(dwb_plugin_name_ + ".trajectory_generator_name", traj_generator_name);
node_->get_parameter(dwb_plugin_name_ + ".goal_checker_name", goal_checker_name);
node_->get_parameter(dwb_plugin_name_ + ".short_circuit_trajectory_evaluation", short_circuit_trajectory_evaluation_);
node_->get_parameter(
dwb_plugin_name_ + ".short_circuit_trajectory_evaluation",
short_circuit_trajectory_evaluation_);

pub_ = std::make_unique<DWBPublisher>(node_, dwb_plugin_name_);
pub_->on_configure();
Expand Down Expand Up @@ -178,14 +187,16 @@ DWBLocalPlanner::loadCritics()
std::string critic_plugin_name = critic_names[i];
std::string plugin_class;

declare_parameter_if_not_declared(node_, dwb_plugin_name_ + "." + critic_plugin_name + ".class",
declare_parameter_if_not_declared(
node_, dwb_plugin_name_ + "." + critic_plugin_name + ".class",
rclcpp::ParameterValue(critic_plugin_name));
node_->get_parameter(dwb_plugin_name_ + "." + critic_plugin_name + ".class", plugin_class);

plugin_class = resolveCriticClassName(plugin_class);

TrajectoryCritic::Ptr plugin = critic_loader_.createUniqueInstance(plugin_class);
RCLCPP_INFO(node_->get_logger(),
RCLCPP_INFO(
node_->get_logger(),
"Using critic \"%s\" (%s)", critic_plugin_name.c_str(), plugin_class.c_str());
critics_.push_back(plugin);
try {
Expand All @@ -202,7 +213,8 @@ void
DWBLocalPlanner::loadBackwardsCompatibleParameters()
{
std::vector<std::string> critic_names;
RCLCPP_INFO(node_->get_logger(),
RCLCPP_INFO(
node_->get_logger(),
"DWBLocalPlanner", "No critics configured! Using the default set.");
critic_names.push_back("RotateToGoal"); // discards trajectories that move forward when
// already at goal
Expand All @@ -227,7 +239,8 @@ DWBLocalPlanner::loadBackwardsCompatibleParameters()
declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".PathDist.scale");
declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".GoalDist.scale");
declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".ObstacleFootprint.scale");
declare_parameter_if_not_declared(node_,
declare_parameter_if_not_declared(
node_,
dwb_plugin_name_ + ".ObstacleFootprint.max_scaling_factor");
declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".ObstacleFootprint.scaling_speed");

Expand Down Expand Up @@ -255,20 +268,23 @@ DWBLocalPlanner::isGoalReached(
const geometry_msgs::msg::Twist & velocity)
{
if (global_plan_.poses.size() == 0) {
RCLCPP_WARN(rclcpp::get_logger(
RCLCPP_WARN(
rclcpp::get_logger(
"DWBLocalPlanner"), "Cannot check if the goal is reached without the goal being set!");
return false;
}
nav_2d_msgs::msg::Pose2DStamped local_start_pose2d, goal_pose2d, local_goal_pose2d;

nav_2d_utils::transformPose(tf_, costmap_ros_->getGlobalFrameID(),
nav_2d_utils::transformPose(
tf_, costmap_ros_->getGlobalFrameID(),
nav_2d_utils::poseStampedToPose2D(pose),
local_start_pose2d, transform_tolerance_);

goal_pose2d.header.frame_id = global_plan_.header.frame_id;
goal_pose2d.pose = global_plan_.poses.back();

nav_2d_utils::transformPose(tf_, costmap_ros_->getGlobalFrameID(), goal_pose2d,
nav_2d_utils::transformPose(
tf_, costmap_ros_->getGlobalFrameID(), goal_pose2d,
local_goal_pose2d, transform_tolerance_);

geometry_msgs::msg::PoseStamped local_start_pose, local_goal_pose;
Expand All @@ -277,7 +293,7 @@ DWBLocalPlanner::isGoalReached(

bool ret = goal_checker_->isGoalReached(local_start_pose.pose, local_goal_pose.pose, velocity);
if (ret) {
RCLCPP_WARN(rclcpp::get_logger("DWBLocalPlanner"), "Goal reached!");
RCLCPP_INFO(rclcpp::get_logger("DWBLocalPlanner"), "Goal reached!");
}
return ret;
}
Expand Down Expand Up @@ -333,7 +349,8 @@ DWBLocalPlanner::prepareGlobalPlan(

goal_pose.header.frame_id = global_plan_.header.frame_id;
goal_pose.pose = global_plan_.poses.back();
nav_2d_utils::transformPose(tf_, costmap_ros_->getGlobalFrameID(), goal_pose,
nav_2d_utils::transformPose(
tf_, costmap_ros_->getGlobalFrameID(), goal_pose,
goal_pose, transform_tolerance_);
}

Expand Down Expand Up @@ -446,7 +463,8 @@ DWBLocalPlanner::coreScoringAlgorithm(
if (debug_trajectory_details_) {
RCLCPP_ERROR(rclcpp::get_logger("DWBLocalPlanner"), "%s", tracker.getMessage().c_str());
for (auto const & x : tracker.getPercentages()) {
RCLCPP_ERROR(rclcpp::get_logger(
RCLCPP_ERROR(
rclcpp::get_logger(
"DWBLocalPlanner"), "%.2f: %10s/%s", x.second,
x.first.first.c_str(), x.first.second.c_str());
}
Expand Down Expand Up @@ -509,8 +527,9 @@ DWBLocalPlanner::transformGlobalPlan(

// let's get the pose of the robot in the frame of the plan
nav_2d_msgs::msg::Pose2DStamped robot_pose;
if (!nav_2d_utils::transformPose(tf_, global_plan_.header.frame_id, pose,
robot_pose, transform_tolerance_))
if (!nav_2d_utils::transformPose(
tf_, global_plan_.header.frame_id, pose,
robot_pose, transform_tolerance_))
{
throw dwb_core::
PlannerTFException("Unable to transform robot pose into global plan's frame");
Expand Down Expand Up @@ -580,7 +599,8 @@ DWBLocalPlanner::transformGlobalPlan(
nav_2d_msgs::msg::Pose2DStamped stamped_pose, transformed_pose;
stamped_pose.header.frame_id = global_plan_.header.frame_id;
stamped_pose.pose = global_plan_pose;
nav_2d_utils::transformPose(tf_, transformed_plan.header.frame_id,
nav_2d_utils::transformPose(
tf_, transformed_plan.header.frame_id,
stamped_pose, transformed_pose, transform_tolerance_);
return transformed_pose.pose;
};
Expand All @@ -606,5 +626,6 @@ DWBLocalPlanner::transformGlobalPlan(
} // namespace dwb_core

// Register this controller as a nav2_core plugin
PLUGINLIB_EXPORT_CLASS(dwb_core::DWBLocalPlanner,
PLUGINLIB_EXPORT_CLASS(
dwb_core::DWBLocalPlanner,
nav2_core::Controller)
21 changes: 14 additions & 7 deletions nav2_dwb_controller/dwb_core/src/publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,19 +57,26 @@ DWBPublisher::DWBPublisher(
const std::string & plugin_name)
: node_(node), plugin_name_(plugin_name)
{
declare_parameter_if_not_declared(node_, plugin_name + ".publish_evaluation",
declare_parameter_if_not_declared(
node_, plugin_name + ".publish_evaluation",
rclcpp::ParameterValue(true));
declare_parameter_if_not_declared(node_, plugin_name + ".publish_global_plan",
declare_parameter_if_not_declared(
node_, plugin_name + ".publish_global_plan",
rclcpp::ParameterValue(true));
declare_parameter_if_not_declared(node_, plugin_name + ".publish_transformed_plan",
declare_parameter_if_not_declared(
node_, plugin_name + ".publish_transformed_plan",
rclcpp::ParameterValue(true));
declare_parameter_if_not_declared(node_, plugin_name + ".publish_local_plan",
declare_parameter_if_not_declared(
node_, plugin_name + ".publish_local_plan",
rclcpp::ParameterValue(true));
declare_parameter_if_not_declared(node_, plugin_name + ".publish_trajectories",
declare_parameter_if_not_declared(
node_, plugin_name + ".publish_trajectories",
rclcpp::ParameterValue(true));
declare_parameter_if_not_declared(node_, plugin_name + ".publish_cost_grid_pc",
declare_parameter_if_not_declared(
node_, plugin_name + ".publish_cost_grid_pc",
rclcpp::ParameterValue(false));
declare_parameter_if_not_declared(node_, plugin_name + ".marker_lifetime",
declare_parameter_if_not_declared(
node_, plugin_name + ".marker_lifetime",
rclcpp::ParameterValue(0.1));
}

Expand Down
53 changes: 26 additions & 27 deletions nav2_dwb_controller/dwb_core/src/trajectory_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,61 +39,60 @@

namespace dwb_local_planner
{
const geometry_msgs::msg::Pose2D& getClosestPose(const dwb_msgs::msg::Trajectory2D& trajectory, const double time_offset)
const geometry_msgs::msg::Pose2D & getClosestPose(
const dwb_msgs::msg::Trajectory2D & trajectory,
const double time_offset)
{
rclcpp::Duration goal_time = rclcpp::Duration::from_seconds(time_offset);
const unsigned int num_poses = trajectory.poses.size();
if (num_poses == 0)
{
if (num_poses == 0) {
throw nav2_core::PlannerException("Cannot call getClosestPose on empty trajectory.");
}
unsigned int closest_index = num_poses;
double closest_diff = 0.0;
for (unsigned int i=0; i < num_poses; ++i)
{
for (unsigned int i = 0; i < num_poses; ++i) {
double diff = std::fabs((rclcpp::Duration(trajectory.time_offsets[i]) - goal_time).seconds());
if (closest_index == num_poses || diff < closest_diff)
{
if (closest_index == num_poses || diff < closest_diff) {
closest_index = i;
closest_diff = diff;
}
if (goal_time < rclcpp::Duration(trajectory.time_offsets[i]))
{
if (goal_time < rclcpp::Duration(trajectory.time_offsets[i])) {
break;
}
}
return trajectory.poses[closest_index];
}

geometry_msgs::msg::Pose2D projectPose(const dwb_msgs::msg::Trajectory2D& trajectory, const double time_offset)
geometry_msgs::msg::Pose2D projectPose(
const dwb_msgs::msg::Trajectory2D & trajectory,
const double time_offset)
{
rclcpp::Duration goal_time = rclcpp::Duration::from_seconds(time_offset);
const unsigned int num_poses = trajectory.poses.size();
if (num_poses == 0)
{
if (num_poses == 0) {
throw nav2_core::PlannerException("Cannot call projectPose on empty trajectory.");
}
if (goal_time <= (trajectory.time_offsets[0]))
{
if (goal_time <= (trajectory.time_offsets[0])) {
return trajectory.poses[0];
}
else if (goal_time >= rclcpp::Duration(trajectory.time_offsets[num_poses - 1]))
{
} else if (goal_time >= rclcpp::Duration(trajectory.time_offsets[num_poses - 1])) {
return trajectory.poses[num_poses - 1];
}

for (unsigned int i=0; i < num_poses - 1; ++i)
{
if (goal_time >= rclcpp::Duration(trajectory.time_offsets[i]) && goal_time < rclcpp::Duration(trajectory.time_offsets[i+1]))
for (unsigned int i = 0; i < num_poses - 1; ++i) {
if (goal_time >= rclcpp::Duration(trajectory.time_offsets[i]) &&
goal_time < rclcpp::Duration(trajectory.time_offsets[i + 1]))
{
double time_diff = (rclcpp::Duration(trajectory.time_offsets[i+1]) - rclcpp::Duration(trajectory.time_offsets[i])).seconds();
double ratio = (goal_time - rclcpp::Duration(trajectory.time_offsets[i])).seconds() / time_diff;
double time_diff =
(rclcpp::Duration(trajectory.time_offsets[i + 1]) -
rclcpp::Duration(trajectory.time_offsets[i])).seconds();
double ratio = (goal_time - rclcpp::Duration(trajectory.time_offsets[i])).seconds() /
time_diff;
double inv_ratio = 1.0 - ratio;
const geometry_msgs::msg::Pose2D& pose_a = trajectory.poses[i];
const geometry_msgs::msg::Pose2D& pose_b = trajectory.poses[i + 1];
const geometry_msgs::msg::Pose2D & pose_a = trajectory.poses[i];
const geometry_msgs::msg::Pose2D & pose_b = trajectory.poses[i + 1];
geometry_msgs::msg::Pose2D projected;
projected.x = pose_a.x * inv_ratio + pose_b.x * ratio;
projected.y = pose_a.y * inv_ratio + pose_b.y * ratio;
projected.x = pose_a.x * inv_ratio + pose_b.x * ratio;
projected.y = pose_a.y * inv_ratio + pose_b.y * ratio;
projected.theta = pose_a.theta * inv_ratio + pose_b.theta * ratio;
return projected;
}
Expand All @@ -104,4 +103,4 @@ geometry_msgs::msg::Pose2D projectPose(const dwb_msgs::msg::Trajectory2D& trajec
}


} // namespace dwb_local_planner
} // namespace dwb_local_planner
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ class RotateToGoalCritic : public dwb_core::TrajectoryCritic
* @param traj Trajectory to score
* @return numeric score
*/
virtual double scoreRotation(const dwb_msgs::msg::Trajectory2D& traj);
virtual double scoreRotation(const dwb_msgs::msg::Trajectory2D & traj);

private:
bool in_window_;
Expand Down
3 changes: 2 additions & 1 deletion nav2_dwb_controller/dwb_critics/src/base_obstacle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,8 @@ void BaseObstacleCritic::onInit()
{
costmap_ = costmap_ros_->getCostmap();

nav2_util::declare_parameter_if_not_declared(nh_,
nav2_util::declare_parameter_if_not_declared(
nh_,
dwb_plugin_name_ + "." + name_ + ".sum_scores", rclcpp::ParameterValue(false));
nh_->get_parameter(dwb_plugin_name_ + "." + name_ + ".sum_scores", sum_scores_);
}
Expand Down
Loading

0 comments on commit 0ada5a4

Please sign in to comment.