00001
00031 #include <ubiquity_motor/motor_message.h>
00032 #include <gtest/gtest.h>
00033
00034 TEST(ubiquity_motor_message, motor_message_commandtype) {
00035 MotorMessage mc;
00036
00037 mc.setType(MotorMessage::TYPE_READ);
00038 ASSERT_EQ(MotorMessage::TYPE_READ, mc.getType());
00039
00040 mc.setType(MotorMessage::TYPE_WRITE);
00041 ASSERT_EQ(MotorMessage::TYPE_WRITE, mc.getType());
00042 }
00043
00044 TEST(ubiquity_motor_message, motor_message_commandtype_invalid) {
00045 MotorMessage mc;
00046
00047 mc.setType(static_cast<MotorMessage::MessageTypes>(0xAB));
00048 ASSERT_NE(0xAB, mc.getType());
00049 }
00050
00051 TEST(ubiquity_motor_message, motor_message_commandtype_overflow) {
00052 MotorMessage mc;
00053
00054 mc.setType(static_cast<MotorMessage::MessageTypes>(0xFFFFFF));
00055 ASSERT_NE(0xFFFFFF, mc.getType());
00056 }
00057
00058 TEST(ubiquity_motor_message, motor_message_commandtype_neg) {
00059 MotorMessage mc;
00060
00061 mc.setType(static_cast<MotorMessage::MessageTypes>(-0xAA));
00062 ASSERT_NE(-0xAA, mc.getType());
00063 ASSERT_NE(0xAA, mc.getType());
00064 }
00065
00066 TEST(ubiquity_motor_message, motor_message_register) {
00067 MotorMessage mc;
00068
00069 mc.setRegister(MotorMessage::REG_BRAKE_STOP);
00070 ASSERT_EQ(MotorMessage::REG_BRAKE_STOP, mc.getRegister());
00071 ASSERT_NE(MotorMessage::REG_STOP_START, mc.getRegister());
00072 }
00073
00074 TEST(ubiquity_motor_message, motor_message_register_invalid) {
00075 MotorMessage mc;
00076
00077 mc.setRegister(static_cast<MotorMessage::Registers>(0x05));
00078 ASSERT_NE(0x05, mc.getRegister());
00079 }
00080
00081 TEST(ubiquity_motor_message, motor_message_register_overflow) {
00082 MotorMessage mc;
00083
00084 mc.setRegister(static_cast<MotorMessage::Registers>(0xFFFFFF));
00085 ASSERT_NE(0xFFFFFF, mc.getRegister());
00086 }
00087
00088 TEST(ubiquity_motor_message, motor_message_register_neg) {
00089 MotorMessage mc;
00090
00091 mc.setRegister(static_cast<MotorMessage::Registers>(-0x07));
00092 ASSERT_NE(-0x07, mc.getRegister());
00093 ASSERT_NE(0x07, mc.getRegister());
00094 }
00095
00096 TEST(ubiquity_motor_message, motor_message_data_64bit_pos) {
00097 MotorMessage mc;
00098 int64_t i = 0xABC;
00099 mc.setData(i);
00100 ASSERT_EQ(0xABC, mc.getData());
00101 }
00102
00103 TEST(ubiquity_motor_message, motor_message_data_64bit_zero) {
00104 MotorMessage mc;
00105 int64_t i = 0;
00106 mc.setData(i);
00107 ASSERT_EQ(0, mc.getData());
00108 }
00109
00110 TEST(ubiquity_motor_message, motor_message_data_64bit_neg) {
00111 MotorMessage mc;
00112 int64_t i = -0xABC;
00113 mc.setData(i);
00114 ASSERT_EQ(-0xABC, mc.getData());
00115 }
00116
00117 TEST(ubiquity_motor_message, motor_message_data_32bit_pos) {
00118 MotorMessage mc;
00119 int32_t i = 0xABC;
00120 mc.setData(i);
00121 ASSERT_EQ(0xABC, mc.getData());
00122 }
00123
00124 TEST(ubiquity_motor_message, motor_message_data_32bit_zero) {
00125 MotorMessage mc;
00126 int32_t i = 0;
00127 mc.setData(i);
00128 ASSERT_EQ(0, mc.getData());
00129 }
00130
00131 TEST(ubiquity_motor_message, motor_message_data_32bit_neg) {
00132 MotorMessage mc;
00133 int32_t i = -0xABC;
00134 mc.setData(i);
00135 ASSERT_EQ(-0xABC, mc.getData());
00136 }
00137
00138 TEST(ubiquity_motor_message, motor_message_data_16bit_pos) {
00139 MotorMessage mc;
00140 int16_t i = 0xABC;
00141 mc.setData(i);
00142 ASSERT_EQ(0xABC, mc.getData());
00143 }
00144
00145 TEST(ubiquity_motor_message, motor_message_data_16bit_zero) {
00146 MotorMessage mc;
00147 int16_t i = 0;
00148 mc.setData(i);
00149 ASSERT_EQ(0, mc.getData());
00150 }
00151
00152 TEST(ubiquity_motor_message, motor_message_data_16bit_neg) {
00153 MotorMessage mc;
00154 int16_t i = -0xABC;
00155 mc.setData(i);
00156 ASSERT_EQ(-0xABC, mc.getData());
00157 }
00158
00159 TEST(ubiquity_motor_message, motor_message_data_8bit_pos) {
00160 MotorMessage mc;
00161 int8_t i = 0x50;
00162 mc.setData(i);
00163 ASSERT_EQ(0x50, mc.getData());
00164 }
00165
00166 TEST(ubiquity_motor_message, motor_message_data_8bit_zero) {
00167 MotorMessage mc;
00168 int8_t i = 0;
00169 mc.setData(i);
00170 ASSERT_EQ(0, mc.getData());
00171 }
00172
00173 TEST(ubiquity_motor_message, motor_message_data_8bit_neg) {
00174 MotorMessage mc;
00175 int8_t i = -0x50;
00176 mc.setData(i);
00177 ASSERT_EQ(-0x50, mc.getData());
00178 }
00179
00180 TEST(ubiquity_motor_message, motor_message_serialize) {
00181 MotorMessage mc;
00182 mc.setData(300);
00183 mc.setType(MotorMessage::TYPE_WRITE);
00184 mc.setRegister(MotorMessage::REG_LEFT_SPEED_SET);
00185
00186 uint8_t arr[] = {0x7E, 0x02, 0xBB, 0x07, 0x00, 0x00, 0x01, 0x2C, 0x0E};
00187
00188 std::vector<uint8_t> expect(arr, arr + sizeof(arr)/ sizeof(uint8_t));
00189
00190 ASSERT_EQ(expect, mc.serialize());
00191 }
00192
00193 TEST(ubiquity_motor_message, motor_message_deserialize_good) {
00194 MotorMessage mc;
00195
00196
00197 uint8_t arr[] = {0x7E, 0x02, 0xBB, 0x07, 0x00, 0x00, 0x01, 0x2C, 0x0E};
00198
00199 std::vector<uint8_t> input(arr, arr + sizeof(arr)/ sizeof(uint8_t));
00200
00201 ASSERT_EQ(0, mc.deserialize(input));
00202 ASSERT_EQ(300, mc.getData());
00203 ASSERT_EQ(MotorMessage::TYPE_WRITE, mc.getType());
00204 ASSERT_EQ(MotorMessage::REG_LEFT_SPEED_SET, mc.getRegister());
00205 }
00206
00207 TEST(ubiquity_motor_message, motor_message_deserialize_bad_delimeter) {
00208 MotorMessage mc;
00209
00210
00211 uint8_t arr[] = {0x67, 0x02, 0xBB, 0x07, 0x00, 0x00, 0x00, 0x00, 0x3B};
00212
00213 std::vector<uint8_t> input(arr, arr + sizeof(arr)/ sizeof(uint8_t));
00214
00215 ASSERT_EQ(1, mc.deserialize(input));
00216 }
00217
00218 TEST(ubiquity_motor_message, motor_message_deserialize_bad_protocol) {
00219 MotorMessage mc;
00220
00221
00222 uint8_t arr[] = {0x7E, 0x01, 0xBB, 0x07, 0x00, 0x00, 0x00, 0x00, 0x3C};
00223
00224 std::vector<uint8_t> input(arr, arr + sizeof(arr)/ sizeof(uint8_t));
00225
00226 ASSERT_EQ(2, mc.deserialize(input));
00227 }
00228
00229 TEST(ubiquity_motor_message, motor_message_deserialize_bad_checksum) {
00230 MotorMessage mc;
00231
00232
00233 uint8_t arr1[] = {0x7E, 0x02, 0xBB, 0x07, 0x00, 0x00, 0x01, 0x2C, 0x0F};
00234
00235 std::vector<uint8_t> input1(arr1, arr1 + sizeof(arr1)/ sizeof(uint8_t));
00236
00237 ASSERT_EQ(3, mc.deserialize(input1));
00238 }
00239
00240 TEST(ubiquity_motor_message, motor_message_deserialize_bad_type) {
00241 MotorMessage mc;
00242
00243
00244 uint8_t arr1[] = {0x7E, 0x02, 0xBA, 0x07, 0x00, 0x00, 0x01, 0x2C, 0x0F};
00245
00246 std::vector<uint8_t> input1(arr1, arr1 + sizeof(arr1)/ sizeof(uint8_t));
00247
00248 ASSERT_EQ(4, mc.deserialize(input1));
00249 }
00250
00251 TEST(ubiquity_motor_message, motor_message_deserialize_bad_register) {
00252 MotorMessage mc;
00253
00254
00255 uint8_t arr[] = {0x7E, 0x02, 0xBB, 0x30, 0x00, 0x00, 0x01, 0x2C, 0xE5};
00256
00257 std::vector<uint8_t> input(arr, arr + sizeof(arr)/ sizeof(uint8_t));
00258
00259 ASSERT_EQ(5, mc.deserialize(input));
00260 }
00261
00262 int main(int argc, char **argv){
00263 testing::InitGoogleTest(&argc, argv);
00264 return RUN_ALL_TESTS();
00265 }