1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 10:00:48 +02:00

Added tests

This commit is contained in:
Simon Rasmussen
2017-03-07 02:50:46 +01:00
parent 7828304e37
commit aa26bb5996
7 changed files with 383 additions and 10 deletions

7
tests/main.cpp Normal file
View File

@@ -0,0 +1,7 @@
#include "gtest/gtest.h"
int main(int argc, char** argv)
{
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}

View File

105
tests/ur/robot_mode.cpp Normal file
View File

@@ -0,0 +1,105 @@
#include <gtest/gtest.h>
#include "ur_modern_driver/ur/robot_mode.h"
#include "ur_modern_driver/bin_parser.h"
#include "ur_modern_driver/log.h"
#include "ur_modern_driver/types.h"
#include "ur_modern_driver/test/utils.h"
#include "ur_modern_driver/test/random_data.h"
TEST(RobotModeData_V1_X, testRandomDataParsing)
{
RandomDataTest rdt(24);
BinParser bp = rdt.getParser();
RobotModeData_V1_X state;
ASSERT_TRUE(state.parseWith(bp)) << "parse() returned false";
ASSERT_EQ(rdt.getNext<uint64_t>(), state.timestamp);
ASSERT_EQ(rdt.getNext<bool>(), state.physical_robot_connected);
ASSERT_EQ(rdt.getNext<bool>(), state.real_robot_enabled);
ASSERT_EQ(rdt.getNext<bool>(), state.robot_power_on);
ASSERT_EQ(rdt.getNext<bool>(), state.emergency_stopped);
ASSERT_EQ(rdt.getNext<bool>(), state.security_stopped);
ASSERT_EQ(rdt.getNext<bool>(), state.program_running);
ASSERT_EQ(rdt.getNext<bool>(), state.program_paused);
ASSERT_EQ(rdt.getNext<robot_mode_V1_X>(), state.robot_mode);
ASSERT_EQ(rdt.getNext<double>(), state.speed_fraction);
ASSERT_TRUE(bp.empty()) << "Did not consume all data";
}
TEST(RobotModeData_V3_0__1, testRandomDataParsing)
{
RandomDataTest rdt(33);
BinParser bp = rdt.getParser();
RobotModeData_V3_0__1 state;
ASSERT_TRUE(state.parseWith(bp)) << "parse() returned false";
ASSERT_EQ(rdt.getNext<uint64_t>(), state.timestamp);
ASSERT_EQ(rdt.getNext<bool>(), state.physical_robot_connected);
ASSERT_EQ(rdt.getNext<bool>(), state.real_robot_enabled);
ASSERT_EQ(rdt.getNext<bool>(), state.robot_power_on);
ASSERT_EQ(rdt.getNext<bool>(), state.emergency_stopped);
ASSERT_EQ(rdt.getNext<bool>(), state.protective_stopped);
ASSERT_EQ(rdt.getNext<bool>(), state.program_running);
ASSERT_EQ(rdt.getNext<bool>(), state.program_paused);
ASSERT_EQ(rdt.getNext<robot_mode_V3_X>(), state.robot_mode);
ASSERT_EQ(rdt.getNext<robot_control_mode_V3_X>(), state.control_mode);
ASSERT_EQ(rdt.getNext<double>(), state.target_speed_fraction);
ASSERT_EQ(rdt.getNext<double>(), state.speed_scaling);
ASSERT_TRUE(bp.empty()) << "Did not consume all data";
}
TEST(RobotModeData_V3_2, testRandomDataParsing)
{
RandomDataTest rdt(41);
BinParser bp = rdt.getParser();
RobotModeData_V3_2 state;
ASSERT_TRUE(state.parseWith(bp)) << "parse() returned false";
ASSERT_EQ(rdt.getNext<uint64_t>(), state.timestamp);
ASSERT_EQ(rdt.getNext<bool>(), state.physical_robot_connected);
ASSERT_EQ(rdt.getNext<bool>(), state.real_robot_enabled);
ASSERT_EQ(rdt.getNext<bool>(), state.robot_power_on);
ASSERT_EQ(rdt.getNext<bool>(), state.emergency_stopped);
ASSERT_EQ(rdt.getNext<bool>(), state.protective_stopped);
ASSERT_EQ(rdt.getNext<bool>(), state.program_running);
ASSERT_EQ(rdt.getNext<bool>(), state.program_paused);
ASSERT_EQ(rdt.getNext<robot_mode_V3_X>(), state.robot_mode);
ASSERT_EQ(rdt.getNext<robot_control_mode_V3_X>(), state.control_mode);
ASSERT_EQ(rdt.getNext<double>(), state.target_speed_fraction);
ASSERT_EQ(rdt.getNext<double>(), state.speed_scaling);
ASSERT_EQ(rdt.getNext<double>(), state.target_speed_fraction_limit);
ASSERT_TRUE(bp.empty()) << "Did not consume all data";
}
TEST(RobotModeData_V1_X, testTooSmallBuffer)
{
RandomDataTest rdt(10);
BinParser bp = rdt.getParser();
RobotModeData_V1_X state;
EXPECT_FALSE(state.parseWith(bp)) << "parse() should fail when buffer not big enough";
}
TEST(RobotModeData_V3_0__1, testTooSmallBuffer)
{
RandomDataTest rdt(10);
BinParser bp = rdt.getParser();
RobotModeData_V3_0__1 state;
EXPECT_FALSE(state.parseWith(bp)) << "parse() should fail when buffer not big enough";
}
TEST(RobotModeData_V3_2, testTooSmallBuffer)
{
RandomDataTest rdt(10);
BinParser bp = rdt.getParser();
RobotModeData_V3_2 state;
EXPECT_FALSE(state.parseWith(bp)) << "parse() should fail when buffer not big enough";
}

192
tests/ur/rt_state.cpp Normal file
View File

@@ -0,0 +1,192 @@
#include <gtest/gtest.h>
#include "ur_modern_driver/ur/rt_state.h"
#include "ur_modern_driver/bin_parser.h"
#include "ur_modern_driver/log.h"
#include "ur_modern_driver/types.h"
#include "ur_modern_driver/test/utils.h"
#include "ur_modern_driver/test/random_data.h"
TEST(RTState_V1_6__7, testRandomDataParsing)
{
RandomDataTest rdt(764);
BinParser bp = rdt.getParser(true);
RTState_V1_6__7 state;
EXPECT_TRUE(state.parseWith(bp)) << "parse() returned false";
ASSERT_EQ(rdt.getNext<double>(), state.time);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.q_target);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.qd_target);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.qdd_target);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.i_target);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.m_target);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.q_actual);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.qd_actual);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.i_actual);
ASSERT_EQ(rdt.getNext<double3_t>(), state.tool_accelerometer_values);
rdt.skip(sizeof(double) * 15);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.tcp_force);
ASSERT_EQ(rdt.getNext<cartesian_coord_t>(), state.tool_vector_actual);
ASSERT_EQ(rdt.getNext<cartesian_coord_t>(), state.tcp_speed_actual);
ASSERT_EQ(rdt.getNext<uint64_t>(), state.digital_inputs);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.motor_temperatures);
ASSERT_EQ(rdt.getNext<double>(), state.controller_time);
rdt.skip(sizeof(double)); // skip unused value
ASSERT_EQ(rdt.getNext<double>(), state.robot_mode);
EXPECT_TRUE(bp.empty()) << "Did not consume all data";
}
TEST(RTState_V1_8, testRandomDataParsing)
{
RandomDataTest rdt(812);
BinParser bp = rdt.getParser(true);
RTState_V1_8 state;
EXPECT_TRUE(state.parseWith(bp)) << "parse() returned false";
ASSERT_EQ(rdt.getNext<double>(), state.time);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.q_target);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.qd_target);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.qdd_target);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.i_target);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.m_target);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.q_actual);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.qd_actual);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.i_actual);
ASSERT_EQ(rdt.getNext<double3_t>(), state.tool_accelerometer_values);
rdt.skip(sizeof(double) * 15);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.tcp_force);
ASSERT_EQ(rdt.getNext<cartesian_coord_t>(), state.tool_vector_actual);
ASSERT_EQ(rdt.getNext<cartesian_coord_t>(), state.tcp_speed_actual);
ASSERT_EQ(rdt.getNext<uint64_t>(), state.digital_inputs);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.motor_temperatures);
ASSERT_EQ(rdt.getNext<double>(), state.controller_time);
rdt.skip(sizeof(double)); // skip unused value
ASSERT_EQ(rdt.getNext<double>(), state.robot_mode);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.joint_modes);
EXPECT_TRUE(bp.empty()) << "Did not consume all data";
}
TEST(RTState_V3_0__1, testRandomDataParsing)
{
RandomDataTest rdt(1044);
BinParser bp = rdt.getParser(true);
RTState_V3_0__1 state;
EXPECT_TRUE(state.parseWith(bp)) << "parse() returned false";
ASSERT_EQ(rdt.getNext<double>(), state.time);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.q_target);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.qd_target);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.qdd_target);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.i_target);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.m_target);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.q_actual);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.qd_actual);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.i_actual);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.i_control);
ASSERT_EQ(rdt.getNext<cartesian_coord_t>(), state.tool_vector_actual);
ASSERT_EQ(rdt.getNext<cartesian_coord_t>(), state.tcp_speed_actual);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.tcp_force);
ASSERT_EQ(rdt.getNext<cartesian_coord_t>(), state.tool_vector_target);
ASSERT_EQ(rdt.getNext<cartesian_coord_t>(), state.tcp_speed_target);
ASSERT_EQ(rdt.getNext<uint64_t>(), state.digital_inputs);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.motor_temperatures);
ASSERT_EQ(rdt.getNext<double>(), state.controller_time);
rdt.skip(sizeof(double)); // skip unused value
ASSERT_EQ(rdt.getNext<double>(), state.robot_mode);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.joint_modes);
ASSERT_EQ(rdt.getNext<double>(), state.safety_mode);
rdt.skip(sizeof(double) * 6);
ASSERT_EQ(rdt.getNext<double3_t>(), state.tool_accelerometer_values);
rdt.skip(sizeof(double) * 6);
ASSERT_EQ(rdt.getNext<double>(), state.speed_scaling);
ASSERT_EQ(rdt.getNext<double>(), state.linear_momentum_norm);
rdt.skip(sizeof(double) * 2);
ASSERT_EQ(rdt.getNext<double>(), state.v_main);
ASSERT_EQ(rdt.getNext<double>(), state.v_robot);
ASSERT_EQ(rdt.getNext<double>(), state.i_robot);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.v_actual);
EXPECT_TRUE(bp.empty()) << "Did not consume all data";
}
TEST(RTState_V3_2__3, testRandomDataParsing)
{
RandomDataTest rdt(1060);
BinParser bp = rdt.getParser(true);
RTState_V3_2__3 state;
EXPECT_TRUE(state.parseWith(bp)) << "parse() returned false";
ASSERT_EQ(rdt.getNext<double>(), state.time);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.q_target);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.qd_target);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.qdd_target);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.i_target);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.m_target);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.q_actual);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.qd_actual);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.i_actual);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.i_control);
ASSERT_EQ(rdt.getNext<cartesian_coord_t>(), state.tool_vector_actual);
ASSERT_EQ(rdt.getNext<cartesian_coord_t>(), state.tcp_speed_actual);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.tcp_force);
ASSERT_EQ(rdt.getNext<cartesian_coord_t>(), state.tool_vector_target);
ASSERT_EQ(rdt.getNext<cartesian_coord_t>(), state.tcp_speed_target);
ASSERT_EQ(rdt.getNext<uint64_t>(), state.digital_inputs);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.motor_temperatures);
ASSERT_EQ(rdt.getNext<double>(), state.controller_time);
rdt.skip(sizeof(double)); // skip unused value
ASSERT_EQ(rdt.getNext<double>(), state.robot_mode);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.joint_modes);
ASSERT_EQ(rdt.getNext<double>(), state.safety_mode);
rdt.skip(sizeof(double) * 6);
ASSERT_EQ(rdt.getNext<double3_t>(), state.tool_accelerometer_values);
rdt.skip(sizeof(double) * 6);
ASSERT_EQ(rdt.getNext<double>(), state.speed_scaling);
ASSERT_EQ(rdt.getNext<double>(), state.linear_momentum_norm);
rdt.skip(sizeof(double) * 2);
ASSERT_EQ(rdt.getNext<double>(), state.v_main);
ASSERT_EQ(rdt.getNext<double>(), state.v_robot);
ASSERT_EQ(rdt.getNext<double>(), state.i_robot);
ASSERT_DOUBLE_ARRAY_EQ(rdt.getNext<double>(), state.v_actual);
ASSERT_EQ(rdt.getNext<uint64_t>(), state.digital_outputs);
ASSERT_EQ(rdt.getNext<double>(), state.program_state);
EXPECT_TRUE(bp.empty()) << "did not consume all data";
}
TEST(RTState_V1_6__7, testTooSmallBuffer)
{
RandomDataTest rdt(10);
BinParser bp = rdt.getParser(true);
RTState_V1_6__7 state;
EXPECT_FALSE(state.parseWith(bp)) << "parse() should fail when buffer not big enough";
}
TEST(RTState_V1_8, testTooSmallBuffer)
{
RandomDataTest rdt(10);
BinParser bp = rdt.getParser(true);
RTState_V1_8 state;
EXPECT_FALSE(state.parseWith(bp)) << "parse() should fail when buffer not big enough";
}
TEST(RTState_V3_0__1, testTooSmallBuffer)
{
RandomDataTest rdt(10);
BinParser bp = rdt.getParser(true);
RTState_V3_0__1 state;
EXPECT_FALSE(state.parseWith(bp)) << "parse() should fail when buffer not big enough";
}
TEST(RTState_V3_2__3, testTooSmallBuffer)
{
RandomDataTest rdt(10);
BinParser bp = rdt.getParser(true);
RTState_V3_2__3 state;
EXPECT_FALSE(state.parseWith(bp)) << "parse() should fail when buffer not big enough";
}