Skip to content

Commit

Permalink
Update linting
Browse files Browse the repository at this point in the history
Signed-off-by: huiyulhy <[email protected]>
  • Loading branch information
huiyulhy committed Sep 12, 2024
1 parent 5a8b465 commit dad2bce
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ 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 for trajectory
/// @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
Expand Down
10 changes: 5 additions & 5 deletions nav2_dwb_controller/dwb_plugins/src/standard_traj_generator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ void StandardTrajectoryGenerator::initialize(

nav2_util::declare_parameter_if_not_declared(
nh,
plugin_name + ".limit_vel_cmd_in_traj_", rclcpp::ParameterValue(false));
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
Expand All @@ -93,7 +93,7 @@ void StandardTrajectoryGenerator::initialize(
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_);
nh->get_parameter(plugin_name + ".limit_vel_cmd_in_traj", limit_vel_cmd_in_traj_);
}

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

// update the position of the robot using the velocities passed in
Expand Down

0 comments on commit dad2bce

Please sign in to comment.