Skip to content

Commit

Permalink
Reduce variable scope
Browse files Browse the repository at this point in the history
  • Loading branch information
at-wat committed Apr 2, 2024
1 parent 374fcf5 commit 9466b9a
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions src/ypspur_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,6 @@ class YpspurRosNode
int key_;
bool simulate_;
bool wait_convergence_of_joint_trajectory_angle_vel_;
bool exit_on_time_jump_;

double tf_time_offset_;

Expand Down Expand Up @@ -455,7 +454,8 @@ class YpspurRosNode
}
pnh_.param(
"wait_convergence_of_joint_trajectory_angle_vel", wait_convergence_of_joint_trajectory_angle_vel_, true);
pnh_.param("exit_on_time_jump", exit_on_time_jump_, false);
bool exit_on_time_jump;
pnh_.param("exit_on_time_jump", exit_on_time_jump, false);
pnh_.param("ypspur_bin", ypspur_bin_, std::string("ypspur-coordinator"));
pnh_.param("param_file", param_file_, std::string(""));
pnh_.param("tf_time_offset", tf_time_offset_, 0.0);
Expand Down Expand Up @@ -661,7 +661,7 @@ class YpspurRosNode
args.push_back(std::string("--enable-get-digital-io"));
if (simulate_)
args.push_back(std::string("--without-device"));
if (exit_on_time_jump_)
if (exit_on_time_jump)
args.push_back(std::string("--exit-on-time-jump"));
if (param_file_.size() > 0)
{
Expand Down

0 comments on commit 9466b9a

Please sign in to comment.