Skip to content

Commit

Permalink
[JTC] Fix typos, implicit cast, const member functions (backport #748)
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Nov 15, 2023
1 parent b0ea83f commit e39a355
Show file tree
Hide file tree
Showing 5 changed files with 19 additions and 19 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -257,7 +257,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
bool reset();

JOINT_TRAJECTORY_CONTROLLER_PUBLIC
bool has_active_trajectory();
bool has_active_trajectory() const;

using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1636,7 +1636,7 @@ void JointTrajectoryController::resize_joint_trajectory_point_command(
}
}

bool JointTrajectoryController::has_active_trajectory()
bool JointTrajectoryController::has_active_trajectory() const
{
return traj_external_point_ptr_ != nullptr && traj_external_point_ptr_->has_trajectory_msg();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ joint_trajectory_controller:
i: {
type: double,
default_value: 0.0,
description: "Intigral gain for PID"
description: "Integral gain for PID"
}
d: {
type: double,
Expand All @@ -119,7 +119,7 @@ joint_trajectory_controller:
i_clamp: {
type: double,
default_value: 0.0,
description: "Integrale clamp. Symmetrical in both positive and negative direction."
description: "Integral clamp. Symmetrical in both positive and negative direction."
}
ff_velocity_scale: {
type: double,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1827,9 +1827,9 @@ TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_later_co
// set command values to NaN
for (size_t i = 0; i < 3; ++i)
{
joint_pos_[i] = 3.1 + i;
joint_vel_[i] = 0.25 + i;
joint_acc_[i] = 0.02 + i / 10.0;
joint_pos_[i] = 3.1 + static_cast<double>(i);
joint_vel_[i] = 0.25 + static_cast<double>(i);
joint_acc_[i] = 0.02 + static_cast<double>(i) / 10.0;
}
SetUpAndActivateTrajectoryController(executor, {is_open_loop_parameters}, true);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -108,31 +108,31 @@ class TestableJointTrajectoryController

void trigger_declare_parameters() { param_listener_->declare_params(); }

trajectory_msgs::msg::JointTrajectoryPoint get_current_state_when_offset()
trajectory_msgs::msg::JointTrajectoryPoint get_current_state_when_offset() const
{
return last_commanded_state_;
}
bool has_position_state_interface() { return has_position_state_interface_; }
bool has_position_state_interface() const { return has_position_state_interface_; }

bool has_velocity_state_interface() { return has_velocity_state_interface_; }
bool has_velocity_state_interface() const { return has_velocity_state_interface_; }

bool has_acceleration_state_interface() { return has_acceleration_state_interface_; }
bool has_acceleration_state_interface() const { return has_acceleration_state_interface_; }

bool has_position_command_interface() { return has_position_command_interface_; }
bool has_position_command_interface() const { return has_position_command_interface_; }

bool has_velocity_command_interface() { return has_velocity_command_interface_; }
bool has_velocity_command_interface() const { return has_velocity_command_interface_; }

bool has_acceleration_command_interface() { return has_acceleration_command_interface_; }
bool has_acceleration_command_interface() const { return has_acceleration_command_interface_; }

bool has_effort_command_interface() { return has_effort_command_interface_; }
bool has_effort_command_interface() const { return has_effort_command_interface_; }

bool use_closed_loop_pid_adapter() { return use_closed_loop_pid_adapter_; }
bool use_closed_loop_pid_adapter() const { return use_closed_loop_pid_adapter_; }

bool is_open_loop() { return params_.open_loop_control; }
bool is_open_loop() const { return params_.open_loop_control; }

bool has_active_traj() { return has_active_trajectory(); }
bool has_active_traj() const { return has_active_trajectory(); }

bool has_trivial_traj()
bool has_trivial_traj() const
{
return has_active_trajectory() && traj_external_point_ptr_->has_nontrivial_msg() == false;
}
Expand Down

0 comments on commit e39a355

Please sign in to comment.