Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[DWB] Option to limit velocity commands in trajectory generator #4663

Merged
merged 6 commits into from
Sep 12, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -147,6 +147,9 @@ class StandardTrajectoryGenerator : public dwb_core::TrajectoryGenerator
/// @brief the name of the overlying plugin ID
std::string plugin_name_;

/// @brief Option to limit velocity in the trajectory generator by using current velocity
bool limit_vel_cmd_in_traj_;

/* Backwards Compatibility Parameter: include_last_point
*
* dwa had an off-by-one error built into it.
Expand Down
10 changes: 10 additions & 0 deletions nav2_dwb_controller/dwb_plugins/src/standard_traj_generator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,10 @@
nh,
plugin_name + ".include_last_point", rclcpp::ParameterValue(true));

nav2_util::declare_parameter_if_not_declared(
nh,
plugin_name + ".limit_vel_cmd_in_traj", rclcpp::ParameterValue(false));

/*
* If discretize_by_time, then sim_granularity represents the amount of time that should be between
* two successive points on the trajectory.
Expand All @@ -89,6 +93,7 @@
nh->get_parameter(plugin_name + ".linear_granularity", linear_granularity_);
nh->get_parameter(plugin_name + ".angular_granularity", angular_granularity_);
nh->get_parameter(plugin_name + ".include_last_point", include_last_point_);
nh->get_parameter(plugin_name + ".limit_vel_cmd_in_traj", limit_vel_cmd_in_traj_);
}

void StandardTrajectoryGenerator::initializeIterator(
Expand Down Expand Up @@ -156,9 +161,14 @@
double running_time = 0.0;
std::vector<double> steps = getTimeSteps(cmd_vel);
traj.poses.push_back(start_pose);
bool first_vel = false;
for (double dt : steps) {
// calculate velocities
vel = computeNewVelocity(cmd_vel, vel, dt);
if (!first_vel && limit_vel_cmd_in_traj_) {
traj.velocity = vel;

Check warning on line 169 in nav2_dwb_controller/dwb_plugins/src/standard_traj_generator.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_dwb_controller/dwb_plugins/src/standard_traj_generator.cpp#L169

Added line #L169 was not covered by tests
first_vel = true;
}

// update the position of the robot using the velocities passed in
pose = computeNewPosition(pose, vel, dt);
Expand Down
Loading