Skip to content

Commit

Permalink
fix tests
Browse files Browse the repository at this point in the history
Signed-off-by: ijnek <kenjibrameld@gmail.com>
  • Loading branch information
ijnek committed Jul 27, 2023
1 parent 3c1a621 commit cd40bf3
Show file tree
Hide file tree
Showing 10 changed files with 32 additions and 29 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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 <map>
#include "nao_lola_client/lola_enums.hpp"
Expand Down Expand Up @@ -143,4 +143,4 @@ static const std::map<int, LolaEnums::SkullLeds> head_leds_msg_to_lola

} // namespace IndexConversion

#endif // NAO_LOLA__COMMAND_INDEX_CONVERSION_HPP_
#endif // NAO_LOLA_CLIENT__COMMAND_INDEX_CONVERSION_HPP_
6 changes: 3 additions & 3 deletions nao_lola_client/include/nao_lola_client/connection.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 <string>
#include "boost/asio.hpp"
Expand All @@ -35,4 +35,4 @@ class Connection
rclcpp::Logger logger;
};

#endif // NAO_LOLA__CONNECTION_HPP_
#endif // NAO_LOLA_CLIENT__CONNECTION_HPP_
6 changes: 3 additions & 3 deletions nao_lola_client/include/nao_lola_client/index_conversion.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 <map>
#include "nao_lola_client/lola_enums.hpp"
Expand Down Expand Up @@ -143,4 +143,4 @@ static const std::map<int, LolaEnums::SkullLeds> head_leds_msg_to_lola

} // namespace IndexConversion

#endif // NAO_LOLA__INDEX_CONVERSION_HPP_
#endif // NAO_LOLA_CLIENT__INDEX_CONVERSION_HPP_
6 changes: 3 additions & 3 deletions nao_lola_client/include/nao_lola_client/lola_enums.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -170,4 +170,4 @@ enum class SkullLeds

} // namespace LolaEnums

#endif // NAO_LOLA__LOLA_ENUMS_HPP_
#endif // NAO_LOLA_CLIENT__LOLA_ENUMS_HPP_
6 changes: 3 additions & 3 deletions nao_lola_client/include/nao_lola_client/msgpack_packer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 <string>
#include <vector>
Expand Down Expand Up @@ -68,4 +68,4 @@ class MsgpackPacker
rclcpp::Logger logger;
};

#endif // NAO_LOLA__MSGPACK_PACKER_HPP_
#endif // NAO_LOLA_CLIENT__MSGPACK_PACKER_HPP_
6 changes: 3 additions & 3 deletions nao_lola_client/include/nao_lola_client/msgpack_parser.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 <map>
#include <string>
Expand Down Expand Up @@ -60,4 +60,4 @@ class MsgpackParser
};


#endif // NAO_LOLA__MSGPACK_PARSER_HPP_
#endif // NAO_LOLA_CLIENT__MSGPACK_PARSER_HPP_
9 changes: 5 additions & 4 deletions nao_lola_client/include/nao_lola_client/nao_lola_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 <thread>
#include <memory>
Expand Down Expand Up @@ -73,7 +73,8 @@ class NaoLolaClient : public rclcpp::Node
rclcpp::Publisher<nao_lola_sensor_msgs::msg::RobotConfig>::SharedPtr robot_config_pub;

rclcpp::Subscription<nao_lola_command_msgs::msg::JointPositions>::SharedPtr joint_positions_sub;
rclcpp::Subscription<nao_lola_command_msgs::msg::JointStiffnesses>::SharedPtr joint_stiffnesses_sub;
rclcpp::Subscription<nao_lola_command_msgs::msg::JointStiffnesses>::SharedPtr
joint_stiffnesses_sub;
rclcpp::Subscription<nao_lola_command_msgs::msg::ChestLed>::SharedPtr chest_led_sub;
rclcpp::Subscription<nao_lola_command_msgs::msg::LeftEarLeds>::SharedPtr left_ear_leds_sub;
rclcpp::Subscription<nao_lola_command_msgs::msg::RightEarLeds>::SharedPtr right_ear_leds_sub;
Expand All @@ -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_
Original file line number Diff line number Diff line change
Expand Up @@ -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 <map>
#include "nao_lola_client/lola_enums.hpp"
Expand Down Expand Up @@ -65,4 +65,4 @@ std::map<int, LolaEnums::Joint> flip(std::map<LolaEnums::Joint, int> in)

} // namespace IndexConversion

#endif // NAO_LOLA__SENSOR_INDEX_CONVERSION_HPP_
#endif // NAO_LOLA_CLIENT__SENSOR_INDEX_CONVERSION_HPP_
4 changes: 3 additions & 1 deletion nao_lola_client/test/test_msgpack_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 <memory>

Expand Down Expand Up @@ -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_

0 comments on commit cd40bf3

Please sign in to comment.