Skip to content

Commit 7585d1f

Browse files
huiyulhyjosephduchesne
authored andcommitted
[DWB] Option to limit velocity commands in trajectory generator (ros-navigation#4663)
* Option to limit vel cmd through traj generator Signed-off-by: huiyulhy <lhyleonghuiyu@gmail.com> * Cleanup Signed-off-by: huiyulhy <lhyleonghuiyu@gmail.com> * fix linting Signed-off-by: huiyulhy <lhyleonghuiyu@gmail.com> * Update linting Signed-off-by: huiyulhy <lhyleonghuiyu@gmail.com> * uncrustify Signed-off-by: huiyulhy <lhyleonghuiyu@gmail.com> * uncrustify Signed-off-by: huiyulhy <lhyleonghuiyu@gmail.com> --------- Signed-off-by: huiyulhy <lhyleonghuiyu@gmail.com> Signed-off-by: Joseph Duchesne <josephgeek@gmail.com>
1 parent 0be81df commit 7585d1f

File tree

2 files changed

+13
-0
lines changed

2 files changed

+13
-0
lines changed

nav2_dwb_controller/dwb_plugins/include/dwb_plugins/standard_traj_generator.hpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -147,6 +147,9 @@ class StandardTrajectoryGenerator : public dwb_core::TrajectoryGenerator
147147
/// @brief the name of the overlying plugin ID
148148
std::string plugin_name_;
149149

150+
/// @brief Option to limit velocity in the trajectory generator by using current velocity
151+
bool limit_vel_cmd_in_traj_;
152+
150153
/* Backwards Compatibility Parameter: include_last_point
151154
*
152155
* dwa had an off-by-one error built into it.

nav2_dwb_controller/dwb_plugins/src/standard_traj_generator.cpp

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -75,6 +75,10 @@ void StandardTrajectoryGenerator::initialize(
7575
nh,
7676
plugin_name + ".include_last_point", rclcpp::ParameterValue(true));
7777

78+
nav2_util::declare_parameter_if_not_declared(
79+
nh,
80+
plugin_name + ".limit_vel_cmd_in_traj", rclcpp::ParameterValue(false));
81+
7882
/*
7983
* If discretize_by_time, then sim_granularity represents the amount of time that should be between
8084
* two successive points on the trajectory.
@@ -89,6 +93,7 @@ void StandardTrajectoryGenerator::initialize(
8993
nh->get_parameter(plugin_name + ".linear_granularity", linear_granularity_);
9094
nh->get_parameter(plugin_name + ".angular_granularity", angular_granularity_);
9195
nh->get_parameter(plugin_name + ".include_last_point", include_last_point_);
96+
nh->get_parameter(plugin_name + ".limit_vel_cmd_in_traj", limit_vel_cmd_in_traj_);
9297
}
9398

9499
void StandardTrajectoryGenerator::initializeIterator(
@@ -156,9 +161,14 @@ dwb_msgs::msg::Trajectory2D StandardTrajectoryGenerator::generateTrajectory(
156161
double running_time = 0.0;
157162
std::vector<double> steps = getTimeSteps(cmd_vel);
158163
traj.poses.push_back(start_pose);
164+
bool first_vel = false;
159165
for (double dt : steps) {
160166
// calculate velocities
161167
vel = computeNewVelocity(cmd_vel, vel, dt);
168+
if (!first_vel && limit_vel_cmd_in_traj_) {
169+
traj.velocity = vel;
170+
first_vel = true;
171+
}
162172

163173
// update the position of the robot using the velocities passed in
164174
pose = computeNewPosition(pose, vel, dt);

0 commit comments

Comments
 (0)