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>(0x30));
103  ASSERT_EQ(MotorMessage::REG_BOTH_ODOM, mc.getRegister());
104 }
105 
106 TEST(MotorMessageTest, motor_message_register_invalid) {
107  MotorMessage mc;
108 
109  mc.setRegister(static_cast<MotorMessage::Registers>(0x05));
110  ASSERT_NE(0x05, mc.getRegister());
111 }
112 
113 TEST(MotorMessageTest, motor_message_register_overflow) {
114  MotorMessage mc;
115 
116  mc.setRegister(static_cast<MotorMessage::Registers>(0xFFFFFF));
117  ASSERT_NE(0xFFFFFF, mc.getRegister());
118 }
119 
120 TEST(MotorMessageTest, motor_message_register_neg) {
121  MotorMessage mc;
122 
123  mc.setRegister(static_cast<MotorMessage::Registers>(-0x07));
124  ASSERT_NE(-0x07, mc.getRegister());
125  ASSERT_NE(0x07, mc.getRegister());
126 }
127 
128 TEST(MotorMessageTest, motor_message_data_64bit) {
129  MotorMessage mc;
130  int64_t i = 0xABC;
131  mc.setData(i);
132  ASSERT_EQ(0xABC, mc.getData());
133 
134  i = 0;
135  mc.setData(i);
136  ASSERT_EQ(0, mc.getData());
137 
138  i = -0xABC;
139  mc.setData(i);
140  ASSERT_EQ(-0xABC, mc.getData());
141 }
142 
143 TEST(MotorMessageTest, motor_message_data_32bit) {
144  MotorMessage mc;
145  int32_t i = 0xABC;
146  mc.setData(i);
147  ASSERT_EQ(0xABC, mc.getData());
148 
149  i = 0;
150  mc.setData(i);
151  ASSERT_EQ(0, mc.getData());
152 
153  i = -0xABC;
154  mc.setData(i);
155  ASSERT_EQ(-0xABC, mc.getData());
156 }
157 
158 TEST(MotorMessageTest, motor_message_data_16bit) {
159  MotorMessage mc;
160  int16_t i = 0xABC;
161  mc.setData(i);
162  ASSERT_EQ(0xABC, mc.getData());
163 
164  i = 0;
165  mc.setData(i);
166  ASSERT_EQ(0, mc.getData());
167 
168  i = -0xABC;
169  mc.setData(i);
170  ASSERT_EQ(-0xABC, mc.getData());
171 }
172 
173 TEST(MotorMessageTest, motor_message_data_8bit) {
174  MotorMessage mc;
175  int8_t i = 0x50;
176  mc.setData(i);
177  ASSERT_EQ(0x50, mc.getData());
178 
179  i = 0;
180  mc.setData(i);
181  ASSERT_EQ(0, mc.getData());
182 
183  i = -0x50;
184  mc.setData(i);
185  ASSERT_EQ(-0x50, mc.getData());
186 }
187 
188 TEST(MotorMessageTest, motor_message_serialize) {
189  MotorMessage mc;
190  mc.setData(300);
193 
194  RawMotorMessage expect = {0x7E, 0x3B, 0x2A, 0x00, 0x00, 0x01, 0x2C, 0x6D};
195 
196  ASSERT_EQ(expect, mc.serialize());
197 }
198 
199 TEST(MotorMessageTest, motor_message_deserialize_good) {
200  MotorMessage mc;
201 
202  // Test good message
203  RawMotorMessage input = {0x7E, 0x3B, 0x2A, 0x00, 0x00, 0x01, 0x2C, 0x6D};
204 
205  ASSERT_EQ(0, mc.deserialize(input));
206  ASSERT_EQ(300, mc.getData());
207  ASSERT_EQ(MotorMessage::TYPE_WRITE, mc.getType());
209 }
210 
211 TEST(MotorMessageTest, motor_message_deserialize_delimeter_in_data) {
212  MotorMessage mc;
213 
214  RawMotorMessage input = {0x7E, 0x3B, 0x2A, 0x00, 0x00, 0x01, 0x7E, 0x1B};
215 
216  ASSERT_EQ(0, mc.deserialize(input));
217  ASSERT_EQ(382, mc.getData());
218  ASSERT_EQ(MotorMessage::TYPE_WRITE, mc.getType());
220 }
221 
222 TEST(MotorMessageTest, motor_message_deserialize_bad_delimeter) {
223  MotorMessage mc;
224 
225  // Test bad delimeter with good checksum
226  RawMotorMessage input = {0x67, 0x3B, 0x07, 0x00, 0x00, 0x00, 0x00, 0xBD};
227 
228  ASSERT_EQ(1, mc.deserialize(input));
229 }
230 
231 TEST(MotorMessageTest, motor_message_deserialize_bad_protocol) {
232  MotorMessage mc;
233 
234  // Test bad protocol_verstion with good checksum
235  RawMotorMessage input = {0x7E, 0x2B, 0x07, 0x00, 0x00, 0x00, 0x00, 0x3D};
236 
237  ASSERT_EQ(2, mc.deserialize(input));
238 }
239 
240 TEST(MotorMessageTest, motor_message_deserialize_bad_checksum) {
241  MotorMessage mc;
242 
243  // Test bad checksum
244  RawMotorMessage input = {0x7E, 0x3B, 0x07, 0x00, 0x00, 0x01, 0x2C, 0x0F};
245 
246  ASSERT_EQ(3, mc.deserialize(input));
247 }
248 
249 TEST(MotorMessageTest, motor_message_deserialize_bad_type) {
250  MotorMessage mc;
251 
252  // Test type with good checksum
253  RawMotorMessage input = {0x7E, 0x3F, 0x07, 0x00, 0x00, 0x00, 0x00, 0xB9};
254 
255  ASSERT_EQ(4, mc.deserialize(input));
256 }
257 
258 TEST(MotorMessageTest, motor_message_deserialize_bad_register) {
259  MotorMessage mc;
260 
261  // Test bad register with good checksum
262  RawMotorMessage input = {0x7E, 0x3B, 0x60, 0x00, 0x00, 0x00, 0x2C, 0x38};
263 
264  ASSERT_EQ(5, mc.deserialize(input));
265 }
266 
267 int main(int argc, char **argv) {
268  testing::InitGoogleTest(&argc, argv);
269  return RUN_ALL_TESTS();
270 }
MotorMessage::REG_BOTH_ODOM
@ REG_BOTH_ODOM
Definition: motor_message.h:147
MotorMessage::deserialize
MotorMessage::ErrorCodes deserialize(const RawMotorMessage &serialized)
Definition: motor_message.cc:151
MotorMessage::TYPE_RESPONSE
@ TYPE_RESPONSE
Definition: motor_message.h:77
MotorMessage::getType
MotorMessage::MessageTypes getType() const
Definition: motor_message.cc:112
MotorMessage::REG_BOTH_SPEED_SET
@ REG_BOTH_SPEED_SET
Definition: motor_message.h:142
MotorMessage::REG_BRAKE_STOP
@ REG_BRAKE_STOP
Definition: motor_message.h:84
MotorMessage::TYPE_ERROR
@ TYPE_ERROR
Definition: motor_message.h:78
MotorMessage::TYPE_READ
@ TYPE_READ
Definition: motor_message.h:75
MotorMessage::setData
void setData(int32_t data)
Definition: motor_message.cc:126
MotorMessage::MessageTypes
MessageTypes
Definition: motor_message.h:74
MotorMessage::Registers
Registers
Definition: motor_message.h:82
MotorMessage::serialize
RawMotorMessage serialize() const
Definition: motor_message.cc:141
MotorMessage::TYPE_WRITE
@ TYPE_WRITE
Definition: motor_message.h:76
MotorMessage::getData
int32_t getData() const
Definition: motor_message.cc:135
motor_message.h
MotorMessage::getRegister
MotorMessage::Registers getRegister() const
Definition: motor_message.cc:122
TEST
TEST(MotorMessageTest, motor_message_commandtype)
Definition: motor_message_test.cc:34
MotorMessage::REG_STOP_START
@ REG_STOP_START
Definition: motor_message.h:83
RawMotorMessage
boost::array< uint8_t, 8 > RawMotorMessage
Definition: motor_message.h:38
MotorMessage::setRegister
void setRegister(MotorMessage::Registers reg)
Definition: motor_message.cc:116
MotorMessage::setType
void setType(MotorMessage::MessageTypes type)
Definition: motor_message.cc:106
MotorMessage
Definition: motor_message.h:67
main
int main(int argc, char **argv)
Definition: motor_message_test.cc:267


ubiquity_motor
Author(s):
autogenerated on Thu Nov 16 2023 03:30:55