Skip to content

Commit 6b73cf5

Browse files
[JTC] Fix typos, implicit cast, const member functions (#748)
1 parent 5178503 commit 6b73cf5

5 files changed

Lines changed: 19 additions & 19 deletions

File tree

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -249,7 +249,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
249249
bool reset();
250250

251251
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
252-
bool has_active_trajectory();
252+
bool has_active_trajectory() const;
253253

254254
using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
255255
JOINT_TRAJECTORY_CONTROLLER_PUBLIC

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1517,7 +1517,7 @@ void JointTrajectoryController::resize_joint_trajectory_point_command(
15171517
}
15181518
}
15191519

1520-
bool JointTrajectoryController::has_active_trajectory()
1520+
bool JointTrajectoryController::has_active_trajectory() const
15211521
{
15221522
return traj_external_point_ptr_ != nullptr && traj_external_point_ptr_->has_trajectory_msg();
15231523
}

joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,7 @@ joint_trajectory_controller:
8686
i: {
8787
type: double,
8888
default_value: 0.0,
89-
description: "Intigral gain for PID"
89+
description: "Integral gain for PID"
9090
}
9191
d: {
9292
type: double,
@@ -96,7 +96,7 @@ joint_trajectory_controller:
9696
i_clamp: {
9797
type: double,
9898
default_value: 0.0,
99-
description: "Integrale clamp. Symmetrical in both positive and negative direction."
99+
description: "Integral clamp. Symmetrical in both positive and negative direction."
100100
}
101101
ff_velocity_scale: {
102102
type: double,

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1531,9 +1531,9 @@ TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_later_co
15311531
// set command values to NaN
15321532
for (size_t i = 0; i < 3; ++i)
15331533
{
1534-
joint_pos_[i] = 3.1 + i;
1535-
joint_vel_[i] = 0.25 + i;
1536-
joint_acc_[i] = 0.02 + i / 10.0;
1534+
joint_pos_[i] = 3.1 + static_cast<double>(i);
1535+
joint_vel_[i] = 0.25 + static_cast<double>(i);
1536+
joint_acc_[i] = 0.02 + static_cast<double>(i) / 10.0;
15371537
}
15381538
SetUpAndActivateTrajectoryController(executor, true, {is_open_loop_parameters}, true);
15391539

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -102,31 +102,31 @@ class TestableJointTrajectoryController
102102

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

105-
trajectory_msgs::msg::JointTrajectoryPoint get_current_state_when_offset()
105+
trajectory_msgs::msg::JointTrajectoryPoint get_current_state_when_offset() const
106106
{
107107
return last_commanded_state_;
108108
}
109-
bool has_position_state_interface() { return has_position_state_interface_; }
109+
bool has_position_state_interface() const { return has_position_state_interface_; }
110110

111-
bool has_velocity_state_interface() { return has_velocity_state_interface_; }
111+
bool has_velocity_state_interface() const { return has_velocity_state_interface_; }
112112

113-
bool has_acceleration_state_interface() { return has_acceleration_state_interface_; }
113+
bool has_acceleration_state_interface() const { return has_acceleration_state_interface_; }
114114

115-
bool has_position_command_interface() { return has_position_command_interface_; }
115+
bool has_position_command_interface() const { return has_position_command_interface_; }
116116

117-
bool has_velocity_command_interface() { return has_velocity_command_interface_; }
117+
bool has_velocity_command_interface() const { return has_velocity_command_interface_; }
118118

119-
bool has_acceleration_command_interface() { return has_acceleration_command_interface_; }
119+
bool has_acceleration_command_interface() const { return has_acceleration_command_interface_; }
120120

121-
bool has_effort_command_interface() { return has_effort_command_interface_; }
121+
bool has_effort_command_interface() const { return has_effort_command_interface_; }
122122

123-
bool use_closed_loop_pid_adapter() { return use_closed_loop_pid_adapter_; }
123+
bool use_closed_loop_pid_adapter() const { return use_closed_loop_pid_adapter_; }
124124

125-
bool is_open_loop() { return params_.open_loop_control; }
125+
bool is_open_loop() const { return params_.open_loop_control; }
126126

127-
bool has_active_traj() { return has_active_trajectory(); }
127+
bool has_active_traj() const { return has_active_trajectory(); }
128128

129-
bool has_trivial_traj()
129+
bool has_trivial_traj() const
130130
{
131131
return has_active_trajectory() && traj_external_point_ptr_->has_nontrivial_msg() == false;
132132
}

0 commit comments

Comments
 (0)