Skip to content

Commit

Permalink
optimize header includes from rclcpp and msgpack that were taking long
Browse files Browse the repository at this point in the history
Signed-off-by: Kenji Brameld <kenjibrameld@gmail.com>
  • Loading branch information
ijnek committed Dec 12, 2023
1 parent 233d0e0 commit fe48290
Show file tree
Hide file tree
Showing 9 changed files with 41 additions and 9 deletions.
1 change: 0 additions & 1 deletion nao_lola_client/include/nao_lola_client/connection.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@
#include <string>
#include "boost/asio.hpp"
#include "rclcpp/logger.hpp"
#include "rclcpp/rclcpp.hpp"

#define MSGPACK_READ_LENGTH 896

Expand Down
2 changes: 1 addition & 1 deletion nao_lola_client/include/nao_lola_client/msgpack_parser.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include <map>
#include <string>
#include <vector>
#include "msgpack.hpp"
#include "msgpack/object.hpp"
#include "nao_lola_sensor_msgs/msg/joint_currents.hpp"
#include "nao_lola_sensor_msgs/msg/joint_positions.hpp"
#include "nao_lola_sensor_msgs/msg/joint_stiffnesses.hpp"
Expand Down
4 changes: 3 additions & 1 deletion nao_lola_client/include/nao_lola_client/nao_lola_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,9 @@
#include <thread>
#include <memory>
#include <mutex>
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/node.hpp"
#include "rclcpp/publisher.hpp"
#include "rclcpp/subscription.hpp"
#include "nao_lola_sensor_msgs/msg/joint_positions.hpp"
#include "nao_lola_sensor_msgs/msg/joint_stiffnesses.hpp"
#include "nao_lola_sensor_msgs/msg/joint_temperatures.hpp"
Expand Down
7 changes: 5 additions & 2 deletions nao_lola_client/src/connection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,9 @@

#include <string>
#include "nao_lola_client/connection.hpp"
#include "rclcpp/clock.hpp"
#include "rclcpp/logging.hpp"
#include "rclcpp/utilities.hpp"

#define ENDPOINT "/tmp/robocup"

Expand All @@ -25,9 +28,9 @@ Connection::Connection()
do {
socket.connect(ENDPOINT, ec);
if (ec) {
RCLCPP_WARN_SKIPFIRST_THROTTLE(
RCLCPP_WARN_STREAM_SKIPFIRST_THROTTLE(
logger, clock, 1000,
(std::string{"Could not connect to LoLA, retrying: "} + ec.message()).c_str());
"Could not connect to LoLA, retrying: " << ec.message());
}
} while (ec && rclcpp::ok());
}
Expand Down
11 changes: 9 additions & 2 deletions nao_lola_client/src/msgpack_packer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,16 @@
#include <memory>
#include <vector>
#include "nao_lola_client/msgpack_packer.hpp"
#include "msgpack.hpp"
#include "msgpack/object.hpp"
#include "msgpack/pack.hpp"
#include "msgpack/adaptor/bool.hpp"
#include "msgpack/adaptor/cpp11/array.hpp"
#include "msgpack/adaptor/float.hpp"
#include "msgpack/adaptor/map.hpp"
#include "msgpack/adaptor/string.hpp"
#include "msgpack/zone.hpp"
#include "nao_lola_client/command_index_conversion.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/logging.hpp"

std::string MsgpackPacker::getPacked()
{
Expand Down
6 changes: 6 additions & 0 deletions nao_lola_client/src/msgpack_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,12 @@
#include <vector>
#include <map>
#include <string>
#include "msgpack/object.hpp"
#include "msgpack/adaptor/float.hpp"
#include "msgpack/adaptor/map.hpp"
#include "msgpack/adaptor/string.hpp"
#include "msgpack/adaptor/vector.hpp"
#include "msgpack/unpack.hpp"
#include "nao_lola_client/msgpack_parser.hpp"
#include "nao_lola_client/lola_enums.hpp"
#include "nao_lola_client/sensor_index_conversion.hpp"
Expand Down
2 changes: 1 addition & 1 deletion nao_lola_client/src/nao_lola_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ NaoLolaClient::NaoLolaClient(const rclcpp::NodeOptions & options)
try {
recvData = connection.receive();
} catch (const std::runtime_error & e) {
RCLCPP_ERROR_SKIPFIRST_THROTTLE(get_logger(), *get_clock(), 1000, e.what());
RCLCPP_ERROR_STREAM_SKIPFIRST_THROTTLE(get_logger(), *get_clock(), 1000, e.what());
continue;
}

Expand Down
9 changes: 8 additions & 1 deletion nao_lola_client/test/test_msgpack_packer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,14 @@
#include <vector>
#include <map>
#include <memory>
#include "msgpack.hpp"
#include "msgpack/object.hpp"
#include "msgpack/adaptor/bool.hpp"
#include "msgpack/adaptor/float.hpp"
#include "msgpack/adaptor/map.hpp"
#include "msgpack/adaptor/string.hpp"
#include "msgpack/adaptor/vector.hpp"
#include "msgpack/adaptor/vector_bool.hpp"
#include "msgpack/unpack.hpp"
#include "nao_lola_client/msgpack_packer.hpp"
#include "nao_lola_command_msgs/msg/joint_positions.hpp"
#include "nao_lola_command_msgs/msg/joint_stiffnesses.hpp"
Expand Down
8 changes: 8 additions & 0 deletions nao_lola_client/test/test_msgpack_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,14 @@
#include <map>
#include <string>
#include <memory>
#include "msgpack/object.hpp"
#include "msgpack/adaptor/float.hpp"
#include "msgpack/adaptor/int.hpp"
#include "msgpack/adaptor/vector.hpp"
#include "msgpack/adaptor/map.hpp"
#include "msgpack/adaptor/string.hpp"
#include "msgpack/pack.hpp"
#include "msgpack/zone.hpp"
#include "nao_lola_client/msgpack_parser.hpp"
#include "nao_lola_sensor_msgs/msg/joint_indexes.hpp"

Expand Down

0 comments on commit fe48290

Please sign in to comment.