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

moved calibration to own repository

This commit is contained in:
Felix Mauch
2019-05-27 16:30:21 +02:00
parent ceb00d8d6d
commit 312fe8b1b7
110 changed files with 250 additions and 46 deletions

View File

@@ -0,0 +1,23 @@
/*
* Copyright 2017, 2018 Simon Rasmussen (refactor)
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "gtest/gtest.h"
int main(int argc, char** argv)
{
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}

View File

@@ -0,0 +1,154 @@
/*
* Copyright 2017, 2018 Simon Rasmussen (refactor)
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "ur_rtde_driver/comm/ur/master_board.h"
#include <gtest/gtest.h>
#include "ur_rtde_driver/comm/bin_parser.h"
#include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/comm/test/random_data.h"
#include "ur_rtde_driver/comm/test/utils.h"
#include "ur_rtde_driver/comm/types.h"
using namespace ur_driver;
TEST(MasterBoardData_V1_X, testRandomDataParsing)
{
RandomDataTest rdt(71);
rdt.set<uint8_t>(1, 58); // sets euromap67_interface_installed to true
BinParser bp = rdt.getParser();
MasterBoardData_V1_X state;
ASSERT_TRUE(state.parseWith(bp)) << "parse() returned false";
ASSERT_EQ((rdt.getNext<uint16_t, 10>()), state.digital_input_bits);
ASSERT_EQ((rdt.getNext<uint16_t, 10>()), state.digital_output_bits);
ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_input_range0);
ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_input_range1);
ASSERT_EQ(rdt.getNext<double>(), state.analog_input0);
ASSERT_EQ(rdt.getNext<double>(), state.analog_input1);
ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_output_domain0);
ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_output_domain1);
ASSERT_EQ(rdt.getNext<double>(), state.analog_output0);
ASSERT_EQ(rdt.getNext<double>(), state.analog_output1);
ASSERT_EQ(rdt.getNext<float>(), state.master_board_temperature);
ASSERT_EQ(rdt.getNext<float>(), state.robot_voltage_48V);
ASSERT_EQ(rdt.getNext<float>(), state.robot_current);
ASSERT_EQ(rdt.getNext<float>(), state.master_IO_current);
ASSERT_EQ(rdt.getNext<uint8_t>(), state.master_safety_state);
ASSERT_EQ(rdt.getNext<bool>(), state.master_on_off_state);
ASSERT_EQ(rdt.getNext<bool>(), state.euromap67_interface_installed);
ASSERT_EQ(rdt.getNext<int32_t>(), state.euromap_input_bits);
ASSERT_EQ(rdt.getNext<int32_t>(), state.euromap_output_bits);
ASSERT_EQ(rdt.getNext<int16_t>(), state.euromap_voltage);
ASSERT_EQ(rdt.getNext<int16_t>(), state.euromap_current);
ASSERT_TRUE(bp.empty()) << "Did not consume all data";
}
TEST(MasterBoardData_V3_0__1, testRandomDataParsing)
{
RandomDataTest rdt(83);
rdt.set<uint8_t>(1, 62); // sets euromap67_interface_installed to true
BinParser bp = rdt.getParser();
MasterBoardData_V3_0__1 state;
ASSERT_TRUE(state.parseWith(bp)) << "parse() returned false";
ASSERT_EQ((rdt.getNext<uint32_t, 18>()), state.digital_input_bits);
ASSERT_EQ((rdt.getNext<uint32_t, 18>()), state.digital_output_bits);
ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_input_range0);
ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_input_range1);
ASSERT_EQ(rdt.getNext<double>(), state.analog_input0);
ASSERT_EQ(rdt.getNext<double>(), state.analog_input1);
ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_output_domain0);
ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_output_domain1);
ASSERT_EQ(rdt.getNext<double>(), state.analog_output0);
ASSERT_EQ(rdt.getNext<double>(), state.analog_output1);
ASSERT_EQ(rdt.getNext<float>(), state.master_board_temperature);
ASSERT_EQ(rdt.getNext<float>(), state.robot_voltage_48V);
ASSERT_EQ(rdt.getNext<float>(), state.robot_current);
ASSERT_EQ(rdt.getNext<float>(), state.master_IO_current);
ASSERT_EQ(rdt.getNext<uint8_t>(), state.safety_mode);
ASSERT_EQ(rdt.getNext<bool>(), state.in_reduced_mode);
ASSERT_EQ(rdt.getNext<bool>(), state.euromap67_interface_installed);
ASSERT_EQ(rdt.getNext<int32_t>(), state.euromap_input_bits);
ASSERT_EQ(rdt.getNext<int32_t>(), state.euromap_output_bits);
ASSERT_EQ(rdt.getNext<float>(), state.euromap_voltage);
ASSERT_EQ(rdt.getNext<float>(), state.euromap_current);
rdt.skip(sizeof(uint32_t));
ASSERT_TRUE(bp.empty()) << "Did not consume all data";
}
TEST(MasterBoardData_V3_2, testRandomDataParsing)
{
RandomDataTest rdt(85);
rdt.set<uint8_t>(1, 62); // sets euromap67_interface_installed to true
BinParser bp = rdt.getParser();
MasterBoardData_V3_2 state;
ASSERT_TRUE(state.parseWith(bp)) << "parse() returned false";
ASSERT_EQ((rdt.getNext<uint32_t, 18>()), state.digital_input_bits);
ASSERT_EQ((rdt.getNext<uint32_t, 18>()), state.digital_output_bits);
ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_input_range0);
ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_input_range1);
ASSERT_EQ(rdt.getNext<double>(), state.analog_input0);
ASSERT_EQ(rdt.getNext<double>(), state.analog_input1);
ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_output_domain0);
ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_output_domain1);
ASSERT_EQ(rdt.getNext<double>(), state.analog_output0);
ASSERT_EQ(rdt.getNext<double>(), state.analog_output1);
ASSERT_EQ(rdt.getNext<float>(), state.master_board_temperature);
ASSERT_EQ(rdt.getNext<float>(), state.robot_voltage_48V);
ASSERT_EQ(rdt.getNext<float>(), state.robot_current);
ASSERT_EQ(rdt.getNext<float>(), state.master_IO_current);
ASSERT_EQ(rdt.getNext<uint8_t>(), state.safety_mode);
ASSERT_EQ(rdt.getNext<bool>(), state.in_reduced_mode);
ASSERT_EQ(rdt.getNext<bool>(), state.euromap67_interface_installed);
ASSERT_EQ(rdt.getNext<int32_t>(), state.euromap_input_bits);
ASSERT_EQ(rdt.getNext<int32_t>(), state.euromap_output_bits);
ASSERT_EQ(rdt.getNext<float>(), state.euromap_voltage);
ASSERT_EQ(rdt.getNext<float>(), state.euromap_current);
rdt.skip(sizeof(uint32_t));
ASSERT_EQ(rdt.getNext<uint8_t>(), state.operational_mode_selector_input);
ASSERT_EQ(rdt.getNext<uint8_t>(), state.three_position_enabling_device_input);
ASSERT_TRUE(bp.empty()) << "Did not consume all data";
}
TEST(MasterBoardData_V1_X, testTooSmallBuffer)
{
RandomDataTest rdt(10);
BinParser bp = rdt.getParser();
MasterBoardData_V1_X state;
EXPECT_FALSE(state.parseWith(bp)) << "parse() should fail when buffer not big enough";
}
TEST(MasterBoardData_V3_0__1, testTooSmallBuffer)
{
RandomDataTest rdt(10);
BinParser bp = rdt.getParser();
MasterBoardData_V3_0__1 state;
EXPECT_FALSE(state.parseWith(bp)) << "parse() should fail when buffer not big enough";
}
TEST(MasterBoardData_V3_2, testTooSmallBuffer)
{
RandomDataTest rdt(10);
BinParser bp = rdt.getParser();
MasterBoardData_V3_2 state;
EXPECT_FALSE(state.parseWith(bp)) << "parse() should fail when buffer not big enough";
}

View File

@@ -0,0 +1,116 @@
/*
* Copyright 2017, 2018 Simon Rasmussen (refactor)
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "ur_rtde_driver/comm/ur/robot_mode.h"
#include <gtest/gtest.h>
#include "ur_rtde_driver/comm/bin_parser.h"
#include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/comm/test/random_data.h"
#include "ur_rtde_driver/comm/test/utils.h"
#include "ur_rtde_driver/comm/types.h"
using namespace ur_driver;
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.protective_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";
}

View File

@@ -0,0 +1,210 @@
/*
* Copyright 2017, 2018 Simon Rasmussen (refactor)
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "ur_rtde_driver/comm/ur/rt_state.h"
#include <gtest/gtest.h>
#include "ur_rtde_driver/comm/bin_parser.h"
#include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/comm/test/random_data.h"
#include "ur_rtde_driver/comm/test/utils.h"
#include "ur_rtde_driver/comm/types.h"
using namespace ur_driver;
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";
}