tests/ur/master_board.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017, 2018 Simon Rasmussen (refactor)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
18 #include <gtest/gtest.h>
20 #include "ur_modern_driver/log.h"
23 #include "ur_modern_driver/types.h"
24 
25 TEST(MasterBoardData_V1_X, testRandomDataParsing)
26 {
27  RandomDataTest rdt(71);
28  rdt.set<uint8_t>(1, 58); // sets euromap67_interface_installed to true
29  BinParser bp = rdt.getParser();
31 
32  ASSERT_TRUE(state.parseWith(bp)) << "parse() returned false";
33 
34  ASSERT_EQ((rdt.getNext<uint16_t, 10>()), state.digital_input_bits);
35  ASSERT_EQ((rdt.getNext<uint16_t, 10>()), state.digital_output_bits);
36  ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_input_range0);
37  ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_input_range1);
38  ASSERT_EQ(rdt.getNext<double>(), state.analog_input0);
39  ASSERT_EQ(rdt.getNext<double>(), state.analog_input1);
40  ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_output_domain0);
41  ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_output_domain1);
42  ASSERT_EQ(rdt.getNext<double>(), state.analog_output0);
43  ASSERT_EQ(rdt.getNext<double>(), state.analog_output1);
44  ASSERT_EQ(rdt.getNext<float>(), state.master_board_temperature);
45  ASSERT_EQ(rdt.getNext<float>(), state.robot_voltage_48V);
46  ASSERT_EQ(rdt.getNext<float>(), state.robot_current);
47  ASSERT_EQ(rdt.getNext<float>(), state.master_IO_current);
48  ASSERT_EQ(rdt.getNext<uint8_t>(), state.master_safety_state);
49  ASSERT_EQ(rdt.getNext<bool>(), state.master_on_off_state);
50  ASSERT_EQ(rdt.getNext<bool>(), state.euromap67_interface_installed);
51  ASSERT_EQ(rdt.getNext<int32_t>(), state.euromap_input_bits);
52  ASSERT_EQ(rdt.getNext<int32_t>(), state.euromap_output_bits);
53  ASSERT_EQ(rdt.getNext<int16_t>(), state.euromap_voltage);
54  ASSERT_EQ(rdt.getNext<int16_t>(), state.euromap_current);
55 
56  ASSERT_TRUE(bp.empty()) << "Did not consume all data";
57 }
58 
59 TEST(MasterBoardData_V3_0__1, testRandomDataParsing)
60 {
61  RandomDataTest rdt(83);
62  rdt.set<uint8_t>(1, 62); // sets euromap67_interface_installed to true
63  BinParser bp = rdt.getParser();
65  ASSERT_TRUE(state.parseWith(bp)) << "parse() returned false";
66 
67  ASSERT_EQ((rdt.getNext<uint32_t, 18>()), state.digital_input_bits);
68  ASSERT_EQ((rdt.getNext<uint32_t, 18>()), state.digital_output_bits);
69  ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_input_range0);
70  ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_input_range1);
71  ASSERT_EQ(rdt.getNext<double>(), state.analog_input0);
72  ASSERT_EQ(rdt.getNext<double>(), state.analog_input1);
73  ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_output_domain0);
74  ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_output_domain1);
75  ASSERT_EQ(rdt.getNext<double>(), state.analog_output0);
76  ASSERT_EQ(rdt.getNext<double>(), state.analog_output1);
77  ASSERT_EQ(rdt.getNext<float>(), state.master_board_temperature);
78  ASSERT_EQ(rdt.getNext<float>(), state.robot_voltage_48V);
79  ASSERT_EQ(rdt.getNext<float>(), state.robot_current);
80  ASSERT_EQ(rdt.getNext<float>(), state.master_IO_current);
81  ASSERT_EQ(rdt.getNext<uint8_t>(), state.safety_mode);
82  ASSERT_EQ(rdt.getNext<bool>(), state.in_reduced_mode);
83  ASSERT_EQ(rdt.getNext<bool>(), state.euromap67_interface_installed);
84  ASSERT_EQ(rdt.getNext<int32_t>(), state.euromap_input_bits);
85  ASSERT_EQ(rdt.getNext<int32_t>(), state.euromap_output_bits);
86  ASSERT_EQ(rdt.getNext<float>(), state.euromap_voltage);
87  ASSERT_EQ(rdt.getNext<float>(), state.euromap_current);
88 
89  rdt.skip(sizeof(uint32_t));
90 
91  ASSERT_TRUE(bp.empty()) << "Did not consume all data";
92 }
93 
94 TEST(MasterBoardData_V3_2, testRandomDataParsing)
95 {
96  RandomDataTest rdt(85);
97  rdt.set<uint8_t>(1, 62); // sets euromap67_interface_installed to true
98  BinParser bp = rdt.getParser();
100  ASSERT_TRUE(state.parseWith(bp)) << "parse() returned false";
101 
102  ASSERT_EQ((rdt.getNext<uint32_t, 18>()), state.digital_input_bits);
103  ASSERT_EQ((rdt.getNext<uint32_t, 18>()), state.digital_output_bits);
104  ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_input_range0);
105  ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_input_range1);
106  ASSERT_EQ(rdt.getNext<double>(), state.analog_input0);
107  ASSERT_EQ(rdt.getNext<double>(), state.analog_input1);
108  ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_output_domain0);
109  ASSERT_EQ(rdt.getNext<int8_t>(), state.analog_output_domain1);
110  ASSERT_EQ(rdt.getNext<double>(), state.analog_output0);
111  ASSERT_EQ(rdt.getNext<double>(), state.analog_output1);
112  ASSERT_EQ(rdt.getNext<float>(), state.master_board_temperature);
113  ASSERT_EQ(rdt.getNext<float>(), state.robot_voltage_48V);
114  ASSERT_EQ(rdt.getNext<float>(), state.robot_current);
115  ASSERT_EQ(rdt.getNext<float>(), state.master_IO_current);
116  ASSERT_EQ(rdt.getNext<uint8_t>(), state.safety_mode);
117  ASSERT_EQ(rdt.getNext<bool>(), state.in_reduced_mode);
118  ASSERT_EQ(rdt.getNext<bool>(), state.euromap67_interface_installed);
119  ASSERT_EQ(rdt.getNext<int32_t>(), state.euromap_input_bits);
120  ASSERT_EQ(rdt.getNext<int32_t>(), state.euromap_output_bits);
121  ASSERT_EQ(rdt.getNext<float>(), state.euromap_voltage);
122  ASSERT_EQ(rdt.getNext<float>(), state.euromap_current);
123  rdt.skip(sizeof(uint32_t));
124  ASSERT_EQ(rdt.getNext<uint8_t>(), state.operational_mode_selector_input);
125  ASSERT_EQ(rdt.getNext<uint8_t>(), state.three_position_enabling_device_input);
126 
127  ASSERT_TRUE(bp.empty()) << "Did not consume all data";
128 }
129 
130 TEST(MasterBoardData_V1_X, testTooSmallBuffer)
131 {
132  RandomDataTest rdt(10);
133  BinParser bp = rdt.getParser();
134  MasterBoardData_V1_X state;
135  EXPECT_FALSE(state.parseWith(bp)) << "parse() should fail when buffer not big enough";
136 }
137 
138 TEST(MasterBoardData_V3_0__1, testTooSmallBuffer)
139 {
140  RandomDataTest rdt(10);
141  BinParser bp = rdt.getParser();
143  EXPECT_FALSE(state.parseWith(bp)) << "parse() should fail when buffer not big enough";
144 }
145 
146 TEST(MasterBoardData_V3_2, testTooSmallBuffer)
147 {
148  RandomDataTest rdt(10);
149  BinParser bp = rdt.getParser();
150  MasterBoardData_V3_2 state;
151  EXPECT_FALSE(state.parseWith(bp)) << "parse() should fail when buffer not big enough";
152 }
std::bitset< 10 > digital_output_bits
Definition: master_board.h:64
bool euromap67_interface_installed
Definition: master_board.h:46
uint8_t three_position_enabling_device_input
Definition: master_board.h:107
BinParser getParser(bool skip=false)
Definition: random_data.h:49
std::bitset< 10 > digital_input_bits
Definition: master_board.h:63
virtual bool parseWith(BinParser &bp)
uint8_t operational_mode_selector_input
Definition: master_board.h:106
uint8_t master_safety_state
Definition: master_board.h:66
virtual bool parseWith(BinParser &bp)
virtual bool parseWith(BinParser &bp)
std::bitset< 18 > digital_output_bits
Definition: master_board.h:85
TEST(MasterBoardData_V1_X, testRandomDataParsing)
void set(T data, size_t pos)
Definition: random_data.h:71
void skip(size_t n)
Definition: random_data.h:76
std::bitset< 18 > digital_input_bits
Definition: master_board.h:84


ur_modern_driver
Author(s): Thomas Timm Andersen, Simon Rasmussen
autogenerated on Fri Jun 26 2020 03:37:00