motor_message_test.cc
Go to the documentation of this file.
1 
31 #include <gtest/gtest.h>
33 
34 TEST(MotorMessageTest, motor_message_commandtype) {
35  MotorMessage mc;
36 
38  ASSERT_EQ(MotorMessage::TYPE_READ, mc.getType());
39 
41  ASSERT_EQ(MotorMessage::TYPE_WRITE, mc.getType());
42 
44  ASSERT_EQ(MotorMessage::TYPE_RESPONSE, mc.getType());
45 
47  ASSERT_EQ(MotorMessage::TYPE_ERROR, mc.getType());
48 }
49 
50 TEST(MotorMessageTest, motor_message_commandtype_values) {
51  MotorMessage mc;
52 
53  mc.setType(static_cast<MotorMessage::MessageTypes>(0xA));
54  ASSERT_EQ(MotorMessage::TYPE_READ, mc.getType());
55 
56  mc.setType(static_cast<MotorMessage::MessageTypes>(0xB));
57  ASSERT_EQ(MotorMessage::TYPE_WRITE, mc.getType());
58 
59  mc.setType(static_cast<MotorMessage::MessageTypes>(0xC));
60  ASSERT_EQ(MotorMessage::TYPE_RESPONSE, mc.getType());
61 
62  mc.setType(static_cast<MotorMessage::MessageTypes>(0xD));
63  ASSERT_EQ(MotorMessage::TYPE_ERROR, mc.getType());
64 }
65 
66 TEST(MotorMessageTest, motor_message_commandtype_invalid) {
67  MotorMessage mc;
68 
69  mc.setType(static_cast<MotorMessage::MessageTypes>(0xF));
70  ASSERT_NE(0xAB, mc.getType());
71 }
72 
73 TEST(MotorMessageTest, motor_message_commandtype_overflow) {
74  MotorMessage mc;
75 
76  mc.setType(static_cast<MotorMessage::MessageTypes>(0xFFFFFF));
77  ASSERT_NE(0xFFFFFF, mc.getType());
78 }
79 
80 TEST(MotorMessageTest, motor_message_commandtype_neg) {
81  MotorMessage mc;
82 
83  mc.setType(static_cast<MotorMessage::MessageTypes>(-0xA));
84  ASSERT_NE(-0xAA, mc.getType());
85  ASSERT_NE(0xAA, mc.getType());
86 }
87 
88 TEST(MotorMessageTest, motor_message_register) {
89  MotorMessage mc;
90 
94 }
95 
96 TEST(MotorMessageTest, motor_message_register_values) {
97  MotorMessage mc;
98 
99  mc.setRegister(static_cast<MotorMessage::Registers>(0x01));
100  ASSERT_EQ(MotorMessage::REG_BRAKE_STOP, mc.getRegister());
101 
102  mc.setRegister(static_cast<MotorMessage::Registers>(0x10));
104 
105  mc.setRegister(static_cast<MotorMessage::Registers>(0x0B));
106  ASSERT_EQ(MotorMessage::REG_LEFT_ODOM, mc.getRegister());
107 }
108 
109 TEST(MotorMessageTest, motor_message_register_invalid) {
110  MotorMessage mc;
111 
112  mc.setRegister(static_cast<MotorMessage::Registers>(0x05));
113  ASSERT_NE(0x05, mc.getRegister());
114 }
115 
116 TEST(MotorMessageTest, motor_message_register_overflow) {
117  MotorMessage mc;
118 
119  mc.setRegister(static_cast<MotorMessage::Registers>(0xFFFFFF));
120  ASSERT_NE(0xFFFFFF, mc.getRegister());
121 }
122 
123 TEST(MotorMessageTest, motor_message_register_neg) {
124  MotorMessage mc;
125 
126  mc.setRegister(static_cast<MotorMessage::Registers>(-0x07));
127  ASSERT_NE(-0x07, mc.getRegister());
128  ASSERT_NE(0x07, mc.getRegister());
129 }
130 
131 TEST(MotorMessageTest, motor_message_data_64bit) {
132  MotorMessage mc;
133  int64_t i = 0xABC;
134  mc.setData(i);
135  ASSERT_EQ(0xABC, mc.getData());
136 
137  i = 0;
138  mc.setData(i);
139  ASSERT_EQ(0, mc.getData());
140 
141  i = -0xABC;
142  mc.setData(i);
143  ASSERT_EQ(-0xABC, mc.getData());
144 }
145 
146 TEST(MotorMessageTest, motor_message_data_32bit) {
147  MotorMessage mc;
148  int32_t i = 0xABC;
149  mc.setData(i);
150  ASSERT_EQ(0xABC, mc.getData());
151 
152  i = 0;
153  mc.setData(i);
154  ASSERT_EQ(0, mc.getData());
155 
156  i = -0xABC;
157  mc.setData(i);
158  ASSERT_EQ(-0xABC, mc.getData());
159 }
160 
161 TEST(MotorMessageTest, motor_message_data_16bit) {
162  MotorMessage mc;
163  int16_t i = 0xABC;
164  mc.setData(i);
165  ASSERT_EQ(0xABC, mc.getData());
166 
167  i = 0;
168  mc.setData(i);
169  ASSERT_EQ(0, mc.getData());
170 
171  i = -0xABC;
172  mc.setData(i);
173  ASSERT_EQ(-0xABC, mc.getData());
174 }
175 
176 TEST(MotorMessageTest, motor_message_data_8bit) {
177  MotorMessage mc;
178  int8_t i = 0x50;
179  mc.setData(i);
180  ASSERT_EQ(0x50, mc.getData());
181 
182  i = 0;
183  mc.setData(i);
184  ASSERT_EQ(0, mc.getData());
185 
186  i = -0x50;
187  mc.setData(i);
188  ASSERT_EQ(-0x50, mc.getData());
189 }
190 
191 TEST(MotorMessageTest, motor_message_serialize) {
192  MotorMessage mc;
193  mc.setData(300);
196 
197  RawMotorMessage expect = {0x7E, 0x3B, 0x07, 0x00, 0x00, 0x01, 0x2C, 0x90};
198 
199  ASSERT_EQ(expect, mc.serialize());
200 }
201 
202 TEST(MotorMessageTest, motor_message_deserialize_good) {
203  MotorMessage mc;
204 
205  // Test good message
206  RawMotorMessage input = {0x7E, 0x3B, 0x07, 0x00, 0x00, 0x01, 0x2C, 0x90};
207 
208  ASSERT_EQ(0, mc.deserialize(input));
209  ASSERT_EQ(300, mc.getData());
210  ASSERT_EQ(MotorMessage::TYPE_WRITE, mc.getType());
212 }
213 
214 TEST(MotorMessageTest, motor_message_deserialize_delimeter_in_data) {
215  MotorMessage mc;
216 
217  RawMotorMessage input = {0x7E, 0x3B, 0x07, 0x00, 0x00, 0x01, 0x7E, 0x3E};
218 
219  ASSERT_EQ(0, mc.deserialize(input));
220  ASSERT_EQ(382, mc.getData());
221  ASSERT_EQ(MotorMessage::TYPE_WRITE, mc.getType());
223 }
224 
225 TEST(MotorMessageTest, motor_message_deserialize_bad_delimeter) {
226  MotorMessage mc;
227 
228  // Test bad delimeter with good checksum
229  RawMotorMessage input = {0x67, 0x3B, 0x07, 0x00, 0x00, 0x00, 0x00, 0xBD};
230 
231  ASSERT_EQ(1, mc.deserialize(input));
232 }
233 
234 TEST(MotorMessageTest, motor_message_deserialize_bad_protocol) {
235  MotorMessage mc;
236 
237  // Test bad protocol_verstion with good checksum
238  RawMotorMessage input = {0x7E, 0x2B, 0x07, 0x00, 0x00, 0x00, 0x00, 0x3D};
239 
240  ASSERT_EQ(2, mc.deserialize(input));
241 }
242 
243 TEST(MotorMessageTest, motor_message_deserialize_bad_checksum) {
244  MotorMessage mc;
245 
246  // Test bad checksum
247  RawMotorMessage input = {0x7E, 0x3B, 0x07, 0x00, 0x00, 0x01, 0x2C, 0x0F};
248 
249  ASSERT_EQ(3, mc.deserialize(input));
250 }
251 
252 TEST(MotorMessageTest, motor_message_deserialize_bad_type) {
253  MotorMessage mc;
254 
255  // Test type with good checksum
256  RawMotorMessage input = {0x7E, 0x3F, 0x07, 0x00, 0x00, 0x00, 0x00, 0xB9};
257 
258  ASSERT_EQ(4, mc.deserialize(input));
259 }
260 
261 TEST(MotorMessageTest, motor_message_deserialize_bad_register) {
262  MotorMessage mc;
263 
264  // Test bad register with good checksum
265  RawMotorMessage input = {0x7E, 0x3B, 0x60, 0x00, 0x00, 0x00, 0x2C, 0x38};
266 
267  ASSERT_EQ(5, mc.deserialize(input));
268 }
269 
270 int main(int argc, char **argv) {
271  testing::InitGoogleTest(&argc, argv);
272  return RUN_ALL_TESTS();
273 }
MotorMessage::MessageTypes getType() const
void setData(int32_t data)
MotorMessage::Registers getRegister() const
boost::array< uint8_t, 8 > RawMotorMessage
Definition: motor_message.h:38
TEST(MotorMessageTest, motor_message_commandtype)
RawMotorMessage serialize() const
void setRegister(MotorMessage::Registers reg)
int main(int argc, char **argv)
void setType(MotorMessage::MessageTypes type)
int deserialize(const RawMotorMessage &serialized)
int32_t getData() const


ubiquity_motor
Author(s):
autogenerated on Mon Jun 10 2019 15:37:24