/* * 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 #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(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()), state.digital_input_bits); ASSERT_EQ((rdt.getNext()), state.digital_output_bits); ASSERT_EQ(rdt.getNext(), state.analog_input_range0); ASSERT_EQ(rdt.getNext(), state.analog_input_range1); ASSERT_EQ(rdt.getNext(), state.analog_input0); ASSERT_EQ(rdt.getNext(), state.analog_input1); ASSERT_EQ(rdt.getNext(), state.analog_output_domain0); ASSERT_EQ(rdt.getNext(), state.analog_output_domain1); ASSERT_EQ(rdt.getNext(), state.analog_output0); ASSERT_EQ(rdt.getNext(), state.analog_output1); ASSERT_EQ(rdt.getNext(), state.master_board_temperature); ASSERT_EQ(rdt.getNext(), state.robot_voltage_48V); ASSERT_EQ(rdt.getNext(), state.robot_current); ASSERT_EQ(rdt.getNext(), state.master_IO_current); ASSERT_EQ(rdt.getNext(), state.master_safety_state); ASSERT_EQ(rdt.getNext(), state.master_on_off_state); ASSERT_EQ(rdt.getNext(), state.euromap67_interface_installed); ASSERT_EQ(rdt.getNext(), state.euromap_input_bits); ASSERT_EQ(rdt.getNext(), state.euromap_output_bits); ASSERT_EQ(rdt.getNext(), state.euromap_voltage); ASSERT_EQ(rdt.getNext(), state.euromap_current); ASSERT_TRUE(bp.empty()) << "Did not consume all data"; } TEST(MasterBoardData_V3_0__1, testRandomDataParsing) { RandomDataTest rdt(83); rdt.set(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()), state.digital_input_bits); ASSERT_EQ((rdt.getNext()), state.digital_output_bits); ASSERT_EQ(rdt.getNext(), state.analog_input_range0); ASSERT_EQ(rdt.getNext(), state.analog_input_range1); ASSERT_EQ(rdt.getNext(), state.analog_input0); ASSERT_EQ(rdt.getNext(), state.analog_input1); ASSERT_EQ(rdt.getNext(), state.analog_output_domain0); ASSERT_EQ(rdt.getNext(), state.analog_output_domain1); ASSERT_EQ(rdt.getNext(), state.analog_output0); ASSERT_EQ(rdt.getNext(), state.analog_output1); ASSERT_EQ(rdt.getNext(), state.master_board_temperature); ASSERT_EQ(rdt.getNext(), state.robot_voltage_48V); ASSERT_EQ(rdt.getNext(), state.robot_current); ASSERT_EQ(rdt.getNext(), state.master_IO_current); ASSERT_EQ(rdt.getNext(), state.safety_mode); ASSERT_EQ(rdt.getNext(), state.in_reduced_mode); ASSERT_EQ(rdt.getNext(), state.euromap67_interface_installed); ASSERT_EQ(rdt.getNext(), state.euromap_input_bits); ASSERT_EQ(rdt.getNext(), state.euromap_output_bits); ASSERT_EQ(rdt.getNext(), state.euromap_voltage); ASSERT_EQ(rdt.getNext(), 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(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()), state.digital_input_bits); ASSERT_EQ((rdt.getNext()), state.digital_output_bits); ASSERT_EQ(rdt.getNext(), state.analog_input_range0); ASSERT_EQ(rdt.getNext(), state.analog_input_range1); ASSERT_EQ(rdt.getNext(), state.analog_input0); ASSERT_EQ(rdt.getNext(), state.analog_input1); ASSERT_EQ(rdt.getNext(), state.analog_output_domain0); ASSERT_EQ(rdt.getNext(), state.analog_output_domain1); ASSERT_EQ(rdt.getNext(), state.analog_output0); ASSERT_EQ(rdt.getNext(), state.analog_output1); ASSERT_EQ(rdt.getNext(), state.master_board_temperature); ASSERT_EQ(rdt.getNext(), state.robot_voltage_48V); ASSERT_EQ(rdt.getNext(), state.robot_current); ASSERT_EQ(rdt.getNext(), state.master_IO_current); ASSERT_EQ(rdt.getNext(), state.safety_mode); ASSERT_EQ(rdt.getNext(), state.in_reduced_mode); ASSERT_EQ(rdt.getNext(), state.euromap67_interface_installed); ASSERT_EQ(rdt.getNext(), state.euromap_input_bits); ASSERT_EQ(rdt.getNext(), state.euromap_output_bits); ASSERT_EQ(rdt.getNext(), state.euromap_voltage); ASSERT_EQ(rdt.getNext(), state.euromap_current); rdt.skip(sizeof(uint32_t)); ASSERT_EQ(rdt.getNext(), state.operational_mode_selector_input); ASSERT_EQ(rdt.getNext(), 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"; }