Skip to content

Commit d99826a

Browse files
author
bailaC
authored
Adding changes for Issue-58. (#254)
1 parent 8e40fd5 commit d99826a

File tree

7 files changed

+22
-22
lines changed

7 files changed

+22
-22
lines changed

‎forward_command_controller/src/forward_command_controller.cpp‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -179,7 +179,7 @@ controller_interface::return_type ForwardCommandController::update(
179179
return controller_interface::return_type::ERROR;
180180
}
181181

182-
for (auto index = 0ul; index < command_interfaces_.size(); ++index)
182+
for (size_t index = 0; index < command_interfaces_.size(); ++index)
183183
{
184184
command_interfaces_[index].set_value((*joint_commands)->data[index]);
185185
}

‎joint_state_broadcaster/src/joint_state_broadcaster.cpp‎

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -245,7 +245,7 @@ controller_interface::return_type JointStateBroadcaster::update(
245245
dynamic_joint_state_msg_.header.stamp = time;
246246

247247
// update joint state message and dynamic joint state message
248-
for (auto i = 0ul; i < joint_names_.size(); ++i)
248+
for (size_t i = 0; i < joint_names_.size(); ++i)
249249
{
250250
joint_state_msg_.position[i] =
251251
get_value(name_if_value_mapping_, joint_names_[i], HW_IF_POSITION);
@@ -254,11 +254,11 @@ controller_interface::return_type JointStateBroadcaster::update(
254254
joint_state_msg_.effort[i] = get_value(name_if_value_mapping_, joint_names_[i], HW_IF_EFFORT);
255255
}
256256

257-
for (auto joint_index = 0ul; joint_index < dynamic_joint_state_msg_.joint_names.size();
257+
for (size_t joint_index = 0; joint_index < dynamic_joint_state_msg_.joint_names.size();
258258
++joint_index)
259259
{
260260
const auto & name = dynamic_joint_state_msg_.joint_names[joint_index];
261-
for (auto interface_index = 0ul;
261+
for (size_t interface_index = 0;
262262
interface_index <
263263
dynamic_joint_state_msg_.interface_values[joint_index].interface_names.size();
264264
++interface_index)

‎joint_state_broadcaster/test/test_joint_state_broadcaster.cpp‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -273,7 +273,7 @@ void JointStateBroadcasterTest::test_published_dynamic_joint_state_message(
273273
// we only check that all values in this test are present in the message
274274
// and that it is the same across the interfaces
275275
// for test purposes they are mapped to the same doubles
276-
for (auto i = 0ul; i < dynamic_joint_state_msg.joint_names.size(); ++i)
276+
for (size_t i = 0; i < dynamic_joint_state_msg.joint_names.size(); ++i)
277277
{
278278
ASSERT_THAT(
279279
dynamic_joint_state_msg.interface_values[i].interface_names,

‎joint_trajectory_controller/include/joint_trajectory_controller/tolerances.hpp‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -105,7 +105,7 @@ SegmentTolerances get_segment_tolerances(
105105

106106
tolerances.state_tolerance.resize(n_joints);
107107
tolerances.goal_state_tolerance.resize(n_joints);
108-
for (auto i = 0ul; i < n_joints; ++i)
108+
for (size_t i = 0; i < n_joints; ++i)
109109
{
110110
const std::string prefix = "constraints." + joint_names[i];
111111

‎joint_trajectory_controller/src/joint_trajectory_controller.cpp‎

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -148,7 +148,7 @@ controller_interface::return_type JointTrajectoryController::update(
148148
// changed, but its value only?
149149
auto assign_interface_from_point =
150150
[&, joint_num](auto & joint_inteface, const std::vector<double> & trajectory_point_interface) {
151-
for (auto index = 0ul; index < joint_num; ++index)
151+
for (size_t index = 0; index < joint_num; ++index)
152152
{
153153
joint_inteface[index].get().set_value(trajectory_point_interface[index]);
154154
}
@@ -208,7 +208,7 @@ controller_interface::return_type JointTrajectoryController::update(
208208
// assign_interface_from_point(joint_command_interface_[3], state_desired.effort);
209209
// }
210210

211-
for (auto index = 0ul; index < joint_num; ++index)
211+
for (size_t index = 0; index < joint_num; ++index)
212212
{
213213
compute_error_for_joint(state_error, index, state_current, state_desired);
214214

@@ -314,7 +314,7 @@ void JointTrajectoryController::read_state_from_hardware(JointTrajectoryPoint &
314314
const auto joint_num = joint_names_.size();
315315
auto assign_point_from_interface =
316316
[&, joint_num](std::vector<double> & trajectory_point_interface, const auto & joint_inteface) {
317-
for (auto index = 0ul; index < joint_num; ++index)
317+
for (size_t index = 0; index < joint_num; ++index)
318318
{
319319
trajectory_point_interface[index] = joint_inteface[index].get().get_value();
320320
}
@@ -353,7 +353,7 @@ bool JointTrajectoryController::read_state_from_command_interfaces(JointTrajecto
353353
const auto joint_num = joint_names_.size();
354354
auto assign_point_from_interface =
355355
[&, joint_num](std::vector<double> & trajectory_point_interface, const auto & joint_inteface) {
356-
for (auto index = 0ul; index < joint_num; ++index)
356+
for (size_t index = 0; index < joint_num; ++index)
357357
{
358358
trajectory_point_interface[index] = joint_inteface[index].get().get_value();
359359
}
@@ -793,13 +793,13 @@ CallbackReturn JointTrajectoryController::on_activate(const rclcpp_lifecycle::St
793793
CallbackReturn JointTrajectoryController::on_deactivate(const rclcpp_lifecycle::State &)
794794
{
795795
// TODO(anyone): How to halt when using effort commands?
796-
for (auto index = 0ul; index < joint_names_.size(); ++index)
796+
for (size_t index = 0; index < joint_names_.size(); ++index)
797797
{
798798
joint_command_interface_[0][index].get().set_value(
799799
joint_command_interface_[0][index].get().get_value());
800800
}
801801

802-
for (auto index = 0ul; index < allowed_interface_types_.size(); ++index)
802+
for (size_t index = 0; index < allowed_interface_types_.size(); ++index)
803803
{
804804
joint_command_interface_[index].clear();
805805
joint_state_interface_[index].clear();
@@ -970,7 +970,7 @@ void JointTrajectoryController::fill_partial_goal(
970970

971971
trajectory_msg->joint_names.reserve(joint_names_.size());
972972

973-
for (auto index = 0ul; index < joint_names_.size(); ++index)
973+
for (size_t index = 0; index < joint_names_.size(); ++index)
974974
{
975975
{
976976
if (
@@ -1023,15 +1023,15 @@ void JointTrajectoryController::sort_to_local_joint_order(
10231023
}
10241024
std::vector<double> output;
10251025
output.resize(mapping.size(), 0.0);
1026-
for (auto index = 0ul; index < mapping.size(); ++index)
1026+
for (size_t index = 0; index < mapping.size(); ++index)
10271027
{
10281028
auto map_index = mapping[index];
10291029
output[map_index] = to_remap[index];
10301030
}
10311031
return output;
10321032
};
10331033

1034-
for (auto index = 0ul; index < trajectory_msg->points.size(); ++index)
1034+
for (size_t index = 0; index < trajectory_msg->points.size(); ++index)
10351035
{
10361036
trajectory_msg->points[index].positions =
10371037
remap(trajectory_msg->points[index].positions, mapping_vector);
@@ -1106,7 +1106,7 @@ bool JointTrajectoryController::validate_trajectory_msg(
11061106
}
11071107
}
11081108

1109-
for (auto i = 0ul; i < trajectory.joint_names.size(); ++i)
1109+
for (size_t i = 0; i < trajectory.joint_names.size(); ++i)
11101110
{
11111111
const std::string & incoming_joint_name = trajectory.joint_names[i];
11121112

@@ -1121,7 +1121,7 @@ bool JointTrajectoryController::validate_trajectory_msg(
11211121
}
11221122

11231123
rclcpp::Duration previous_traj_time(0ms);
1124-
for (auto i = 0ul; i < trajectory.points.size(); ++i)
1124+
for (size_t i = 0; i < trajectory.points.size(); ++i)
11251125
{
11261126
if ((i > 0) && (rclcpp::Duration(trajectory.points[i].time_from_start) <= previous_traj_time))
11271127
{

‎joint_trajectory_controller/src/trajectory.cpp‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -106,7 +106,7 @@ bool Trajectory::sample(
106106

107107
// time_from_start + trajectory time is the expected arrival time of trajectory
108108
const auto last_idx = trajectory_msg_->points.size() - 1;
109-
for (auto i = 0ul; i < last_idx; ++i)
109+
for (size_t i = 0; i < last_idx; ++i)
110110
{
111111
const auto & point = trajectory_msg_->points[i];
112112
const auto & next_point = trajectory_msg_->points[i + 1];

‎joint_trajectory_controller/test/test_trajectory_controller.cpp‎

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -971,7 +971,7 @@ TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_first_co
971971
rclcpp::Parameter is_open_loop_parameters("open_loop_control", true);
972972

973973
// set command values to NaN
974-
for (auto i = 0u; i < 3; ++i)
974+
for (size_t i = 0; i < 3; ++i)
975975
{
976976
joint_pos_[i] = std::numeric_limits<double>::quiet_NaN();
977977
joint_vel_[i] = std::numeric_limits<double>::quiet_NaN();
@@ -981,7 +981,7 @@ TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_first_co
981981

982982
auto current_state_when_offset = traj_controller_->get_current_state_when_offset();
983983

984-
for (auto i = 0u; i < 3; ++i)
984+
for (size_t i = 0; i < 3; ++i)
985985
{
986986
EXPECT_EQ(current_state_when_offset.positions[i], joint_state_pos_[i]);
987987

@@ -1022,7 +1022,7 @@ TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_later_co
10221022
rclcpp::Parameter is_open_loop_parameters("open_loop_control", true);
10231023

10241024
// set command values to NaN
1025-
for (auto i = 0u; i < 3; ++i)
1025+
for (size_t i = 0; i < 3; ++i)
10261026
{
10271027
joint_pos_[i] = 3.1 + i;
10281028
joint_vel_[i] = 0.25 + i;
@@ -1032,7 +1032,7 @@ TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_later_co
10321032

10331033
auto current_state_when_offset = traj_controller_->get_current_state_when_offset();
10341034

1035-
for (auto i = 0u; i < 3; ++i)
1035+
for (size_t i = 0; i < 3; ++i)
10361036
{
10371037
EXPECT_EQ(current_state_when_offset.positions[i], joint_pos_[i]);
10381038

0 commit comments

Comments
 (0)