@@ -75,6 +75,10 @@ void StandardTrajectoryGenerator::initialize(
75
75
nh,
76
76
plugin_name + " .include_last_point" , rclcpp::ParameterValue (true ));
77
77
78
+ nav2_util::declare_parameter_if_not_declared (
79
+ nh,
80
+ plugin_name + " .limit_vel_cmd_in_traj" , rclcpp::ParameterValue (false ));
81
+
78
82
/*
79
83
* If discretize_by_time, then sim_granularity represents the amount of time that should be between
80
84
* two successive points on the trajectory.
@@ -89,6 +93,7 @@ void StandardTrajectoryGenerator::initialize(
89
93
nh->get_parameter (plugin_name + " .linear_granularity" , linear_granularity_);
90
94
nh->get_parameter (plugin_name + " .angular_granularity" , angular_granularity_);
91
95
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_);
92
97
}
93
98
94
99
void StandardTrajectoryGenerator::initializeIterator (
@@ -156,9 +161,14 @@ dwb_msgs::msg::Trajectory2D StandardTrajectoryGenerator::generateTrajectory(
156
161
double running_time = 0.0 ;
157
162
std::vector<double > steps = getTimeSteps (cmd_vel);
158
163
traj.poses .push_back (start_pose);
164
+ bool first_vel = false ;
159
165
for (double dt : steps) {
160
166
// calculate velocities
161
167
vel = computeNewVelocity (cmd_vel, vel, dt);
168
+ if (!first_vel && limit_vel_cmd_in_traj_) {
169
+ traj.velocity = vel;
170
+ first_vel = true ;
171
+ }
162
172
163
173
// update the position of the robot using the velocities passed in
164
174
pose = computeNewPosition (pose, vel, dt);
0 commit comments