diff --git a/nao_lola_client/include/nao_lola_client/command_index_conversion.hpp b/nao_lola_client/include/nao_lola_client/command_index_conversion.hpp index 8be95b7..08d0f48 100644 --- a/nao_lola_client/include/nao_lola_client/command_index_conversion.hpp +++ b/nao_lola_client/include/nao_lola_client/command_index_conversion.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NAO_LOLA__COMMAND_INDEX_CONVERSION_HPP_ -#define NAO_LOLA__COMMAND_INDEX_CONVERSION_HPP_ +#ifndef NAO_LOLA_CLIENT__COMMAND_INDEX_CONVERSION_HPP_ +#define NAO_LOLA_CLIENT__COMMAND_INDEX_CONVERSION_HPP_ #include #include "nao_lola_client/lola_enums.hpp" @@ -143,4 +143,4 @@ static const std::map head_leds_msg_to_lola } // namespace IndexConversion -#endif // NAO_LOLA__COMMAND_INDEX_CONVERSION_HPP_ +#endif // NAO_LOLA_CLIENT__COMMAND_INDEX_CONVERSION_HPP_ diff --git a/nao_lola_client/include/nao_lola_client/connection.hpp b/nao_lola_client/include/nao_lola_client/connection.hpp index 956b4cb..e2492f3 100644 --- a/nao_lola_client/include/nao_lola_client/connection.hpp +++ b/nao_lola_client/include/nao_lola_client/connection.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NAO_LOLA__CONNECTION_HPP_ -#define NAO_LOLA__CONNECTION_HPP_ +#ifndef NAO_LOLA_CLIENT__CONNECTION_HPP_ +#define NAO_LOLA_CLIENT__CONNECTION_HPP_ #include #include "boost/asio.hpp" @@ -35,4 +35,4 @@ class Connection rclcpp::Logger logger; }; -#endif // NAO_LOLA__CONNECTION_HPP_ +#endif // NAO_LOLA_CLIENT__CONNECTION_HPP_ diff --git a/nao_lola_client/include/nao_lola_client/index_conversion.hpp b/nao_lola_client/include/nao_lola_client/index_conversion.hpp index 2a1c3f3..8b2c86a 100644 --- a/nao_lola_client/include/nao_lola_client/index_conversion.hpp +++ b/nao_lola_client/include/nao_lola_client/index_conversion.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NAO_LOLA__INDEX_CONVERSION_HPP_ -#define NAO_LOLA__INDEX_CONVERSION_HPP_ +#ifndef NAO_LOLA_CLIENT__INDEX_CONVERSION_HPP_ +#define NAO_LOLA_CLIENT__INDEX_CONVERSION_HPP_ #include #include "nao_lola_client/lola_enums.hpp" @@ -143,4 +143,4 @@ static const std::map head_leds_msg_to_lola } // namespace IndexConversion -#endif // NAO_LOLA__INDEX_CONVERSION_HPP_ +#endif // NAO_LOLA_CLIENT__INDEX_CONVERSION_HPP_ diff --git a/nao_lola_client/include/nao_lola_client/lola_enums.hpp b/nao_lola_client/include/nao_lola_client/lola_enums.hpp index f0b8ce7..50a51f1 100644 --- a/nao_lola_client/include/nao_lola_client/lola_enums.hpp +++ b/nao_lola_client/include/nao_lola_client/lola_enums.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NAO_LOLA__LOLA_ENUMS_HPP_ -#define NAO_LOLA__LOLA_ENUMS_HPP_ +#ifndef NAO_LOLA_CLIENT__LOLA_ENUMS_HPP_ +#define NAO_LOLA_CLIENT__LOLA_ENUMS_HPP_ // The enums are exactly as defined (and in the same order) as what's provided // in "Lola RoboCupper Official Documentation.pdf" sent to all Standard Platform League @@ -170,4 +170,4 @@ enum class SkullLeds } // namespace LolaEnums -#endif // NAO_LOLA__LOLA_ENUMS_HPP_ +#endif // NAO_LOLA_CLIENT__LOLA_ENUMS_HPP_ diff --git a/nao_lola_client/include/nao_lola_client/msgpack_packer.hpp b/nao_lola_client/include/nao_lola_client/msgpack_packer.hpp index 2663a94..7427fdd 100644 --- a/nao_lola_client/include/nao_lola_client/msgpack_packer.hpp +++ b/nao_lola_client/include/nao_lola_client/msgpack_packer.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NAO_LOLA__MSGPACK_PACKER_HPP_ -#define NAO_LOLA__MSGPACK_PACKER_HPP_ +#ifndef NAO_LOLA_CLIENT__MSGPACK_PACKER_HPP_ +#define NAO_LOLA_CLIENT__MSGPACK_PACKER_HPP_ #include #include @@ -68,4 +68,4 @@ class MsgpackPacker rclcpp::Logger logger; }; -#endif // NAO_LOLA__MSGPACK_PACKER_HPP_ +#endif // NAO_LOLA_CLIENT__MSGPACK_PACKER_HPP_ diff --git a/nao_lola_client/include/nao_lola_client/msgpack_parser.hpp b/nao_lola_client/include/nao_lola_client/msgpack_parser.hpp index e38d373..2d15c5a 100644 --- a/nao_lola_client/include/nao_lola_client/msgpack_parser.hpp +++ b/nao_lola_client/include/nao_lola_client/msgpack_parser.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NAO_LOLA__MSGPACK_PARSER_HPP_ -#define NAO_LOLA__MSGPACK_PARSER_HPP_ +#ifndef NAO_LOLA_CLIENT__MSGPACK_PARSER_HPP_ +#define NAO_LOLA_CLIENT__MSGPACK_PARSER_HPP_ #include #include @@ -60,4 +60,4 @@ class MsgpackParser }; -#endif // NAO_LOLA__MSGPACK_PARSER_HPP_ +#endif // NAO_LOLA_CLIENT__MSGPACK_PARSER_HPP_ diff --git a/nao_lola_client/include/nao_lola_client/nao_lola_client.hpp b/nao_lola_client/include/nao_lola_client/nao_lola_client.hpp index 6e0d18a..b065189 100644 --- a/nao_lola_client/include/nao_lola_client/nao_lola_client.hpp +++ b/nao_lola_client/include/nao_lola_client/nao_lola_client.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NAO_LOLA__NAO_LOLA_HPP_ -#define NAO_LOLA__NAO_LOLA_HPP_ +#ifndef NAO_LOLA_CLIENT__NAO_LOLA_CLIENT_HPP_ +#define NAO_LOLA_CLIENT__NAO_LOLA_CLIENT_HPP_ #include #include @@ -73,7 +73,8 @@ class NaoLolaClient : public rclcpp::Node rclcpp::Publisher::SharedPtr robot_config_pub; rclcpp::Subscription::SharedPtr joint_positions_sub; - rclcpp::Subscription::SharedPtr joint_stiffnesses_sub; + rclcpp::Subscription::SharedPtr + joint_stiffnesses_sub; rclcpp::Subscription::SharedPtr chest_led_sub; rclcpp::Subscription::SharedPtr left_ear_leds_sub; rclcpp::Subscription::SharedPtr right_ear_leds_sub; @@ -91,4 +92,4 @@ class NaoLolaClient : public rclcpp::Node std::mutex packer_mutex; }; -#endif // NAO_LOLA__NAO_LOLA_HPP_ +#endif // NAO_LOLA_CLIENT__NAO_LOLA_CLIENT_HPP_ diff --git a/nao_lola_client/include/nao_lola_client/sensor_index_conversion.hpp b/nao_lola_client/include/nao_lola_client/sensor_index_conversion.hpp index d8b9b77..e454011 100644 --- a/nao_lola_client/include/nao_lola_client/sensor_index_conversion.hpp +++ b/nao_lola_client/include/nao_lola_client/sensor_index_conversion.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NAO_LOLA__SENSOR_INDEX_CONVERSION_HPP_ -#define NAO_LOLA__SENSOR_INDEX_CONVERSION_HPP_ +#ifndef NAO_LOLA_CLIENT__SENSOR_INDEX_CONVERSION_HPP_ +#define NAO_LOLA_CLIENT__SENSOR_INDEX_CONVERSION_HPP_ #include #include "nao_lola_client/lola_enums.hpp" @@ -65,4 +65,4 @@ std::map flip(std::map in) } // namespace IndexConversion -#endif // NAO_LOLA__SENSOR_INDEX_CONVERSION_HPP_ +#endif // NAO_LOLA_CLIENT__SENSOR_INDEX_CONVERSION_HPP_ diff --git a/nao_lola_client/test/test_msgpack_parser.cpp b/nao_lola_client/test/test_msgpack_parser.cpp index 091e4cd..8149879 100644 --- a/nao_lola_client/test/test_msgpack_parser.cpp +++ b/nao_lola_client/test/test_msgpack_parser.cpp @@ -182,7 +182,9 @@ TEST_F(TestMsgpackParser, TestJointCurrents) EXPECT_NEAR( jointCurrents.currents.at(nao_lola_sensor_msgs::msg::JointIndexes::HEADYAW), 0.1, 0.000001); - EXPECT_NEAR(jointCurrents.currents.at(nao_lola_sensor_msgs::msg::JointIndexes::RHAND), 0.2, 0.00001); + EXPECT_NEAR( + jointCurrents.currents.at( + nao_lola_sensor_msgs::msg::JointIndexes::RHAND), 0.2, 0.00001); } TEST_F(TestMsgpackParser, TestJointStatuses) diff --git a/nao_lola_conversion/include/nao_lola_conversion/nao_lola_conversion.hpp b/nao_lola_conversion/include/nao_lola_conversion/nao_lola_conversion.hpp index f3a52c6..ef207f0 100644 --- a/nao_lola_conversion/include/nao_lola_conversion/nao_lola_conversion.hpp +++ b/nao_lola_conversion/include/nao_lola_conversion/nao_lola_conversion.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NAO_INTERFACES_BRIDGE__NAO_INTERFACES_BRIDGE_HPP_ -#define NAO_INTERFACES_BRIDGE__NAO_INTERFACES_BRIDGE_HPP_ +#ifndef NAO_LOLA_CONVERSION__NAO_LOLA_CONVERSION_HPP_ +#define NAO_LOLA_CONVERSION__NAO_LOLA_CONVERSION_HPP_ #include @@ -52,4 +52,4 @@ class NaoLolaConversion : public rclcpp::Node } // namespace nao_lola_conversion -#endif // NAO_INTERFACES_BRIDGE__NAO_INTERFACES_BRIDGE_HPP_ +#endif // NAO_LOLA_CONVERSION__NAO_LOLA_CONVERSION_HPP_