Skip to content

Commit ed22c3e

Browse files
authored
Merge pull request #100 from traclabs/hotfix/fix-compiler-warnings
Fix compiler warnings on clang (Fix #103)
2 parents e59dac9 + 538e079 commit ed22c3e

File tree

4 files changed

+9
-9
lines changed

4 files changed

+9
-9
lines changed

ros_trick/ros_src/trick_ros2_control/include/trick_ros2_control/trick_system.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@
2323
#include "rclcpp/macros.hpp"
2424
#include "rclcpp/rclcpp.hpp"
2525
#include "rclcpp_lifecycle/state.hpp"
26-
#include "realtime_tools/realtime_buffer.h"
26+
#include "realtime_tools/realtime_buffer.hpp"
2727
#include "trick_ros2_control/socket.hpp"
2828
#include "trick_ros2_control/utils.hpp"
2929
#include "trick_ros2_control/visibility_control.h"

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

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ double trick_string_convert(const std::string& str)
2424
return num;
2525
}
2626

27-
std::vector<std::string> trick_split_response(std::string& str, const char delim)
27+
std::vector<std::string> trick_split_response(std::string& str, const char /*delim*/)
2828
{
2929
std::stringstream ss(str);
3030
std::string s;
@@ -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: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -82,7 +82,7 @@ hardware_interface::CallbackReturn TrickSystem::on_configure(const rclcpp_lifecy
8282
{
8383
std::string err = "could not connect to Trick server on host: " + trick_hostname_ +
8484
" and port: " + std::to_string(trick_server_port_);
85-
RCLCPP_FATAL(rclcpp::get_logger("TrickSystem"), err.c_str());
85+
RCLCPP_FATAL(rclcpp::get_logger("TrickSystem"), "%s", err.c_str());
8686
return hardware_interface::CallbackReturn::ERROR;
8787
}
8888

@@ -235,12 +235,12 @@ hardware_interface::return_type TrickSystem::read(const rclcpp::Time& /*time*/,
235235
{
236236
RCLCPP_FATAL(rclcpp::get_logger("TrickSystem"),
237237
"size of data received from trick does not match number of "
238-
"declared state variables. Expected: %d. "
239-
"Got: %d",
238+
"declared state variables. Expected: %zu. "
239+
"Got: %zu",
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)