Skip to content

Commit 597f1e2

Browse files
kbrameldkbrameld@traclabs.com
authored andcommitted
fix comparison of integers of different signs: 'int' and 'size_type' (issue #103)
1 parent 583825d commit 597f1e2

File tree

3 files changed

+4
-4
lines changed

3 files changed

+4
-4
lines changed

ros_trick/ros_src/trick_ros2_control/include/trick_ros2_control/utils.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ std::vector<double> trick_response_convert(std::string& response)
4444
{
4545
return result;
4646
}
47-
for (int i = 1; i < responseSplit.size(); i++)
47+
for (size_t i = 1; i < responseSplit.size(); i++)
4848
{
4949
result.push_back(trick_string_convert(responseSplit[i]));
5050
}

ros_trick/ros_src/trick_ros2_control/src/socket.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -81,8 +81,8 @@ std::string Socket::receive()
8181
}
8282

8383
std::string string_buffer = std::string(carry_on_buffer_) + std::string(buffer);
84-
int last_newline_idx = string_buffer.rfind(trick_delimiter_, string_buffer.size() - 1);
85-
int second_last_newline_idx = string_buffer.rfind(trick_delimiter_, string_buffer.size() - 2);
84+
auto last_newline_idx = string_buffer.rfind(trick_delimiter_, string_buffer.size() - 1);
85+
auto second_last_newline_idx = string_buffer.rfind(trick_delimiter_, string_buffer.size() - 2);
8686

8787
// it means that we can clear carry on buffer
8888
if (last_newline_idx == string_buffer.size() - 1)

ros_trick/ros_src/trick_ros2_control/src/trick_system.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -240,7 +240,7 @@ hardware_interface::return_type TrickSystem::read(const rclcpp::Time& /*time*/,
240240
trick_state_variables_.size(), raw_doubles_from_trick.size());
241241
return hardware_interface::return_type::OK;
242242
}
243-
for (int i = 0; i < raw_doubles_from_trick.size(); ++i)
243+
for (size_t i = 0; i < raw_doubles_from_trick.size(); ++i)
244244
{
245245
double value_from_trick = raw_doubles_from_trick[i];
246246
double* const target_state_variable_ptr_ = trick_state_variables_[i].data_ptr;

0 commit comments

Comments
 (0)