Skip to content

Commit

Permalink
Rename class variable to match parameter name
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Nov 14, 2023
1 parent 4ca9e20 commit fd49c22
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -167,8 +167,9 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
std::vector<PidPtr> pids_;
// Feed-forward velocity weight factor when calculating closed loop pid adapter's command
std::vector<double> ff_velocity_scale_;
// Configuration for every joint, if position error is normalized
std::vector<bool> normalize_joint_error_;
// Configuration for every joint if it wraps around (ie. is continuous, position error is
// normalized)
std::vector<bool> joints_angle_wraparound_;
// reserved storage for result of the command when closed loop pid adapter is used
std::vector<double> tmp_command_;

Expand Down
12 changes: 6 additions & 6 deletions joint_trajectory_controller/src/joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ controller_interface::return_type JointTrajectoryController::update(
const JointTrajectoryPoint & desired)
{
// error defined as the difference between current and desired
if (normalize_joint_error_[index])
if (joints_angle_wraparound_[index])
{
// if desired, the shortest_angular_distance is calculated, i.e., the error is
// normalized between -pi<error<pi
Expand Down Expand Up @@ -197,12 +197,12 @@ controller_interface::return_type JointTrajectoryController::update(
if (params_.open_loop_control)
{
traj_external_point_ptr_->set_point_before_trajectory_msg(
time, last_commanded_state_, normalize_joint_error_);
time, last_commanded_state_, joints_angle_wraparound_);
}
else
{
traj_external_point_ptr_->set_point_before_trajectory_msg(
time, state_current_, normalize_joint_error_);
time, state_current_, joints_angle_wraparound_);
}
}

Expand Down Expand Up @@ -727,19 +727,19 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
}

// Configure joint position error normalization from ROS parameters (angle_wraparound)
normalize_joint_error_.resize(dof_);
joints_angle_wraparound_.resize(dof_);
for (size_t i = 0; i < dof_; ++i)
{
const auto & gains = params_.gains.joints_map.at(params_.joints[i]);
if (gains.normalize_error)
{
// TODO(anyone): Remove deprecation warning in the end of 2023
RCLCPP_INFO(logger, "`normalize_error` is deprecated, use `angle_wraparound` instead!");
normalize_joint_error_[i] = gains.normalize_error;
joints_angle_wraparound_[i] = gains.normalize_error;
}
else
{
normalize_joint_error_[i] = gains.angle_wraparound;
joints_angle_wraparound_[i] = gains.angle_wraparound;
}
}

Expand Down

0 comments on commit fd49c22

Please sign in to comment.