test_ulc_node.cpp
Go to the documentation of this file.
1 #include <gtest/gtest.h>
2 #include <ros/ros.h>
3 
4 #include <std_msgs/Bool.h>
5 #include <geometry_msgs/TwistStamped.h>
6 #include <dataspeed_ulc_msgs/UlcCmd.h>
7 #include <dataspeed_ulc_msgs/UlcReport.h>
9 #include <can_msgs/Frame.h>
10 #include "MsgRx.h"
11 
12 using namespace dataspeed_ulc_can;
13 
15 
19 
20 dataspeed_ulc_msgs::UlcCmd g_ulc_cmd;
21 double g_cfg_freq;
22 
23 // Command message scale factors
24 const double LIN_VEL_SCALE_FACTOR = 0.0025;
25 const double YAW_RATE_SCALE_FACTOR = 0.00025;
26 const double CURVATURE_SCALE_FACTOR = 0.0000061;
27 
28 // Config message scale factors
29 const double LINEAR_ACCEL_SCALE_FACTOR = 0.025;
30 const double LINEAR_DECEL_SCALE_FACTOR = 0.025;
31 const double LATERAL_ACCEL_SCALE_FACTOR = 0.05;
32 const double ANGULAR_ACCEL_SCALE_FACTOR = 0.02;
33 
34 // Report message scale factors
35 const double SPEED_REPORT_SCALE_FACTOR = 0.02;
36 const double ACCEL_REPORT_SCALE_FACTOR = 0.05;
37 const double MAX_ANGLE_SCALE_FACTOR = 5.0;
38 const double MAX_RATE_SCALE_FACTOR = 8.0;
39 
47 
48 void recvCan(const can_msgs::FrameConstPtr& msg)
49 {
50  if (!msg->is_rtr && !msg->is_error && !msg->is_extended) {
51  switch (msg->id) {
52  case ID_ULC_CMD:
53  g_msg_ulc_cmd.set(*((MsgUlcCmd*)msg->data.elems));
54  break;
55  case ID_ULC_CONFIG:
56  g_msg_ulc_cfg.set(*((MsgUlcCfg*)msg->data.elems));
57  break;
58  }
59  }
60 }
61 
62 void recvReport(const dataspeed_ulc_msgs::UlcReportConstPtr& msg)
63 {
64  g_msg_ulc_report.set(*msg);
65 }
66 
67 template <class T>
68 static bool waitForMsg(ros::WallDuration dur, const MsgRx<T>& msg_rx)
69 {
70  const ros::WallTime start = ros::WallTime::now();
71  while (true) {
72  if (msg_rx.fresh()) {
73  return true;
74  }
75  if ((ros::WallTime::now() - start) > dur) {
76  return false;
77  }
78  ros::WallDuration(0.001).sleep();
79  }
80 }
81 
82 static bool waitForTopics(ros::WallDuration dur) {
83  const ros::WallTime start = ros::WallTime::now();
84  while (true) {
85  if ((g_sub_can.getNumPublishers() == 1)
86  && (g_sub_report.getNumPublishers() == 1)
87  && (g_pub_ulc_cmd.getNumSubscribers() == 1)
88  && (g_pub_enable.getNumSubscribers() == 1)
89  && (g_pub_twist.getNumSubscribers() == 1)
90  && (g_pub_twist_stamped.getNumSubscribers() == 1)
91  && (g_pub_can.getNumSubscribers() == 1)) {
92  return true;
93  }
94  if ((ros::WallTime::now() - start) > dur) {
95  return false;
96  }
97  ros::WallDuration(0.001).sleep();
98  }
99 }
100 
101 static void checkImmediateCfg()
102 {
104  g_msg_ulc_cfg.clear();
105  g_pub_ulc_cmd.publish(g_ulc_cmd);
106  EXPECT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cfg));
107  EXPECT_NEAR(g_msg_ulc_cfg.stamp().toSec(), stamp.toSec(), 0.01);
108 }
109 
110 TEST(ULCNode, topics)
111 {
112  // Wait for all topics to connect before running other tests
113  ASSERT_TRUE(waitForTopics(ros::WallDuration(2.0)));
114  ros::WallDuration(1.0).sleep();
115 
116  // Call unused function to complete coverage testing
118 }
119 
120 TEST(ULCNode, cfgTiming)
121 {
122  g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
123  g_ulc_cmd.linear_accel = 1.0;
124  g_ulc_cmd.linear_decel = 1.0;
125  g_ulc_cmd.lateral_accel = 1.0;
126  g_ulc_cmd.angular_accel = 1.0;
127 
128  // Publish command messages with the same acceleration limits and make sure
129  // config CAN messages are sent at the nominal rate
130  size_t count = 0;
131  ros::WallTime stamp_old;
133  g_msg_ulc_cfg.clear();
134  while (t_end > ros::WallTime::now()) {
135  g_pub_ulc_cmd.publish(g_ulc_cmd);
136  ros::WallDuration(0.02).sleep();
137  ros::WallTime stamp_new = g_msg_ulc_cfg.stamp();
138  if (!stamp_new.isZero()) {
139  if (!stamp_old.isZero() && (stamp_old != stamp_new)) {
140  EXPECT_NEAR(stamp_old.toSec() + (1.0 / g_cfg_freq), stamp_new.toSec(), 0.01);
141  count++;
142  }
143  stamp_old = stamp_new;
144  }
145  }
146  EXPECT_GE(count, 1);
147 
148  // Change accel limits and make sure config CAN messages are sent immediately
149  g_ulc_cmd.linear_accel = 2.0;
151  g_ulc_cmd.linear_decel = 2.0;
153  g_ulc_cmd.lateral_accel = 2.0;
155  g_ulc_cmd.angular_accel = 2.0;
157 }
158 
159 TEST(ULCNode, cmdRangeSaturation)
160 {
161  g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
162 
163  /*** Underflow tests ******************************************************/
164  g_ulc_cmd.enable_pedals = true;
165  g_ulc_cmd.enable_steering = true;
166  g_ulc_cmd.linear_velocity = (INT16_MIN * LIN_VEL_SCALE_FACTOR) - 1.0;
167  g_ulc_cmd.linear_accel = -1.0;
168  g_ulc_cmd.linear_decel = -1.0;
169  g_ulc_cmd.lateral_accel = -1.0;
170  g_ulc_cmd.angular_accel = -1.0;
171 
172  // Yaw rate steering
173  g_ulc_cmd.yaw_command = (INT16_MIN * YAW_RATE_SCALE_FACTOR) - 0.5;
174  g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE;
175  g_msg_ulc_cmd.clear();
176  g_msg_ulc_cfg.clear();
177  g_pub_ulc_cmd.publish(g_ulc_cmd);
178  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
179  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cfg));
180  EXPECT_EQ(INT16_MIN, g_msg_ulc_cmd.get().linear_velocity);
181  EXPECT_EQ(INT16_MIN, g_msg_ulc_cmd.get().yaw_command);
182  EXPECT_EQ(0, g_msg_ulc_cfg.get().linear_accel);
183  EXPECT_EQ(0, g_msg_ulc_cfg.get().linear_decel);
184  EXPECT_EQ(0, g_msg_ulc_cfg.get().lateral_accel);
185  EXPECT_EQ(0, g_msg_ulc_cfg.get().angular_accel);
186 
187  // Curvature steering
188  g_ulc_cmd.yaw_command = (INT16_MIN * CURVATURE_SCALE_FACTOR) - 0.05;
189  g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::CURVATURE_MODE;
190  g_msg_ulc_cmd.clear();
191  g_msg_ulc_cfg.clear();
192  g_pub_ulc_cmd.publish(g_ulc_cmd);
193  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
194  EXPECT_EQ(INT16_MIN, g_msg_ulc_cmd.get().yaw_command);
195  /**************************************************************************/
196 
197  /*** Overflow tests *******************************************************/
198  g_ulc_cmd.enable_pedals = true;
199  g_ulc_cmd.enable_steering = true;
200  g_ulc_cmd.linear_velocity = (INT16_MAX * LIN_VEL_SCALE_FACTOR) + 1.0;
201  g_ulc_cmd.linear_accel = 100.0;
202  g_ulc_cmd.linear_decel = 100.0;
203  g_ulc_cmd.lateral_accel = 100.0;
204  g_ulc_cmd.angular_accel = 100.0;
205 
206  // Yaw rate steering
207  g_ulc_cmd.yaw_command = (INT16_MAX * YAW_RATE_SCALE_FACTOR) + 0.5;
208  g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE;
209  g_msg_ulc_cmd.clear();
210  g_msg_ulc_cfg.clear();
211  g_pub_ulc_cmd.publish(g_ulc_cmd);
212  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
213  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cfg));
214  EXPECT_EQ(INT16_MAX, g_msg_ulc_cmd.get().linear_velocity);
215  EXPECT_EQ(INT16_MAX, g_msg_ulc_cmd.get().yaw_command);
216  EXPECT_EQ(UINT8_MAX, g_msg_ulc_cfg.get().linear_accel);
217  EXPECT_EQ(UINT8_MAX, g_msg_ulc_cfg.get().linear_decel);
218  EXPECT_EQ(UINT8_MAX, g_msg_ulc_cfg.get().lateral_accel);
219  EXPECT_EQ(UINT8_MAX, g_msg_ulc_cfg.get().angular_accel);
220 
221  // Curvature steering
222  g_ulc_cmd.yaw_command = (INT16_MAX * CURVATURE_SCALE_FACTOR) + 0.05;
223  g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::CURVATURE_MODE;
224  g_msg_ulc_cmd.clear();
225  g_msg_ulc_cfg.clear();
226  g_pub_ulc_cmd.publish(g_ulc_cmd);
227  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
228  EXPECT_EQ(INT16_MAX, g_msg_ulc_cmd.get().yaw_command);
229  /**************************************************************************/
230 
231  /*** +Inf tests ***********************************************************/
232  g_ulc_cmd.enable_pedals = true;
233  g_ulc_cmd.enable_steering = true;
234  g_ulc_cmd.linear_velocity = INFINITY;
235  g_ulc_cmd.linear_accel = INFINITY;
236  g_ulc_cmd.linear_decel = INFINITY;
237  g_ulc_cmd.lateral_accel = INFINITY;
238  g_ulc_cmd.angular_accel = INFINITY;
239 
240  // Yaw rate steering
241  g_ulc_cmd.yaw_command = INFINITY;
242  g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE;
243  g_msg_ulc_cmd.clear();
244  g_msg_ulc_cfg.clear();
245  g_pub_ulc_cmd.publish(g_ulc_cmd);
246  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
247  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cfg));
248  EXPECT_EQ(INT16_MAX, g_msg_ulc_cmd.get().linear_velocity);
249  EXPECT_EQ(INT16_MAX, g_msg_ulc_cmd.get().yaw_command);
250  EXPECT_EQ(UINT8_MAX, g_msg_ulc_cfg.get().linear_accel);
251  EXPECT_EQ(UINT8_MAX, g_msg_ulc_cfg.get().linear_decel);
252  EXPECT_EQ(UINT8_MAX, g_msg_ulc_cfg.get().lateral_accel);
253  EXPECT_EQ(UINT8_MAX, g_msg_ulc_cfg.get().angular_accel);
254 
255  // Curvature steering
256  g_ulc_cmd.yaw_command = INFINITY;
257  g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::CURVATURE_MODE;
258  g_msg_ulc_cmd.clear();
259  g_msg_ulc_cfg.clear();
260  g_pub_ulc_cmd.publish(g_ulc_cmd);
261  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
262  EXPECT_EQ(INT16_MAX, g_msg_ulc_cmd.get().yaw_command);
263  /**************************************************************************/
264 
265  /*** -Inf tests ***********************************************************/
266  g_ulc_cmd.enable_pedals = true;
267  g_ulc_cmd.enable_steering = true;
268  g_ulc_cmd.linear_velocity = -INFINITY;
269  g_ulc_cmd.linear_accel = -INFINITY;
270  g_ulc_cmd.linear_decel = -INFINITY;
271  g_ulc_cmd.lateral_accel = -INFINITY;
272  g_ulc_cmd.angular_accel = -INFINITY;
273 
274  // Yaw rate steering
275  g_ulc_cmd.yaw_command = -INFINITY;
276  g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE;
277  g_msg_ulc_cmd.clear();
278  g_msg_ulc_cfg.clear();
279  g_pub_ulc_cmd.publish(g_ulc_cmd);
280  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
281  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cfg));
282  EXPECT_EQ(INT16_MIN, g_msg_ulc_cmd.get().linear_velocity);
283  EXPECT_EQ(INT16_MIN, g_msg_ulc_cmd.get().yaw_command);
284  EXPECT_EQ(0, g_msg_ulc_cfg.get().linear_accel);
285  EXPECT_EQ(0, g_msg_ulc_cfg.get().linear_decel);
286  EXPECT_EQ(0, g_msg_ulc_cfg.get().lateral_accel);
287  EXPECT_EQ(0, g_msg_ulc_cfg.get().angular_accel);
288 
289  // Curvature steering
290  g_ulc_cmd.yaw_command = -INFINITY;
291  g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::CURVATURE_MODE;
292  g_msg_ulc_cmd.clear();
293  g_msg_ulc_cfg.clear();
294  g_pub_ulc_cmd.publish(g_ulc_cmd);
295  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
296  EXPECT_EQ(INT16_MIN, g_msg_ulc_cmd.get().yaw_command);
297  /**************************************************************************/
298 }
299 
300 TEST(ULCNode, outOfBoundsInputs)
301 {
302  g_msg_ulc_cfg.clear();
303 
304  // NaN in linear velocity field
305  g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
306  g_ulc_cmd.linear_velocity = NAN;
307  g_msg_ulc_cmd.clear();
308  g_pub_ulc_cmd.publish(g_ulc_cmd);
309  EXPECT_FALSE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
310 
311  // NaN in yaw command field
312  g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
313  g_ulc_cmd.yaw_command = NAN;
314  g_msg_ulc_cmd.clear();
315  g_pub_ulc_cmd.publish(g_ulc_cmd);
316  ASSERT_FALSE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
317 
318  // NaN in linear accel field
319  g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
320  g_ulc_cmd.linear_accel = NAN;
321  g_msg_ulc_cmd.clear();
322  g_pub_ulc_cmd.publish(g_ulc_cmd);
323  EXPECT_FALSE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
324 
325  // NaN in linear decel field
326  g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
327  g_ulc_cmd.linear_decel = NAN;
328  g_msg_ulc_cmd.clear();
329  g_pub_ulc_cmd.publish(g_ulc_cmd);
330  EXPECT_FALSE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
331 
332  // NaN in lateral accel field
333  g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
334  g_ulc_cmd.lateral_accel = NAN;
335  g_msg_ulc_cmd.clear();
336  g_pub_ulc_cmd.publish(g_ulc_cmd);
337  EXPECT_FALSE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
338 
339  // NaN in angular accel field
340  g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
341  g_ulc_cmd.angular_accel = NAN;
342  g_msg_ulc_cmd.clear();
343  g_pub_ulc_cmd.publish(g_ulc_cmd);
344  EXPECT_FALSE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
345 
346  // Invalid steering mode
347  g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
348  g_ulc_cmd.steering_mode = 3;
349  g_msg_ulc_cmd.clear();
350  g_pub_ulc_cmd.publish(g_ulc_cmd);
351  EXPECT_FALSE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
352 
353  // Make sure no config messages were sent during this process
354  EXPECT_FALSE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cfg));
355 }
356 
357 TEST(ULCNode, scaleFactors)
358 {
359  g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
360  g_ulc_cmd.linear_velocity = 22.3;
361  g_ulc_cmd.linear_accel = 1.23;
362  g_ulc_cmd.linear_decel = 3.45;
363  g_ulc_cmd.lateral_accel = 5.43;
364  g_ulc_cmd.angular_accel = 3.21;
365 
366  // Yaw rate steering
367  g_ulc_cmd.yaw_command = 0.567;
368  g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE;
369  g_msg_ulc_cmd.clear();
370  g_msg_ulc_cfg.clear();
371  g_pub_ulc_cmd.publish(g_ulc_cmd);
372  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
373  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cfg));
374  EXPECT_EQ((int16_t)(g_ulc_cmd.linear_velocity / LIN_VEL_SCALE_FACTOR), g_msg_ulc_cmd.get().linear_velocity);
375  EXPECT_EQ((int16_t)(g_ulc_cmd.yaw_command / YAW_RATE_SCALE_FACTOR), g_msg_ulc_cmd.get().yaw_command);
376  EXPECT_EQ((int16_t)(g_ulc_cmd.linear_accel / LINEAR_ACCEL_SCALE_FACTOR), g_msg_ulc_cfg.get().linear_accel);
377  EXPECT_EQ((int16_t)(g_ulc_cmd.linear_decel / LINEAR_DECEL_SCALE_FACTOR), g_msg_ulc_cfg.get().linear_decel);
378  EXPECT_EQ((int16_t)(g_ulc_cmd.lateral_accel / LATERAL_ACCEL_SCALE_FACTOR), g_msg_ulc_cfg.get().lateral_accel);
379  EXPECT_EQ((int16_t)(g_ulc_cmd.angular_accel / ANGULAR_ACCEL_SCALE_FACTOR), g_msg_ulc_cfg.get().angular_accel);
380 
381  // Curvature steering
382  g_ulc_cmd.yaw_command = 0.0789;
383  g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::CURVATURE_MODE;
384  g_msg_ulc_cmd.clear();
385  g_pub_ulc_cmd.publish(g_ulc_cmd);
386  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
387  EXPECT_EQ((int16_t)(g_ulc_cmd.yaw_command / CURVATURE_SCALE_FACTOR), g_msg_ulc_cmd.get().yaw_command);
388 }
389 
390 TEST(ULCNode, dbwEnable)
391 {
392  std_msgs::Bool dbw_enabled_msg;
393 
394  g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
395  g_ulc_cmd.enable_pedals = true;
396  g_ulc_cmd.enable_steering = true;
397  g_ulc_cmd.enable_shifting = true;
398  g_ulc_cmd.shift_from_park = true;
399 
400  // Make sure CAN enable signals are false because dbw_enabled was not sent yet
401  g_msg_ulc_cmd.clear();
402  g_pub_ulc_cmd.publish(g_ulc_cmd);
403  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
404  EXPECT_FALSE(g_msg_ulc_cmd.get().enable_pedals);
405  EXPECT_FALSE(g_msg_ulc_cmd.get().enable_steering);
406  EXPECT_FALSE(g_msg_ulc_cmd.get().enable_shifting);
407  EXPECT_FALSE(g_msg_ulc_cmd.get().shift_from_park);
408 
409  // Publish dbw_enabled as true
410  dbw_enabled_msg.data = true;
411  g_pub_enable.publish(dbw_enabled_msg);
412  ros::WallDuration(0.001).sleep();
413 
414  // Send command again and make sure CAN enable signals are true
415  g_msg_ulc_cmd.clear();
416  g_pub_ulc_cmd.publish(g_ulc_cmd);
417  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
418  EXPECT_TRUE(g_msg_ulc_cmd.get().enable_pedals);
419  EXPECT_TRUE(g_msg_ulc_cmd.get().enable_steering);
420  EXPECT_TRUE(g_msg_ulc_cmd.get().enable_shifting);
421  EXPECT_TRUE(g_msg_ulc_cmd.get().shift_from_park);
422 
423  // Publish dbw_enabled as false and make sure CAN enable signals are false
424  dbw_enabled_msg.data = false;
425  g_pub_enable.publish(dbw_enabled_msg);
426  ros::WallDuration(0.05).sleep();
427  g_msg_ulc_cmd.clear();
428  g_pub_ulc_cmd.publish(g_ulc_cmd);
429  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
430  ASSERT_FALSE(g_msg_ulc_cmd.get().enable_pedals);
431  ASSERT_FALSE(g_msg_ulc_cmd.get().enable_steering);
432  ASSERT_FALSE(g_msg_ulc_cmd.get().enable_shifting);
433  ASSERT_FALSE(g_msg_ulc_cmd.get().shift_from_park);
434 }
435 
436 TEST(ULCNode, twistInputs)
437 {
438  geometry_msgs::Twist twist_cmd;
439  twist_cmd.linear.x = 22.0;
440  twist_cmd.angular.z = 0.2;
441  ros::WallDuration(1.0).sleep();
442 
443  g_msg_ulc_cmd.clear();
444  g_msg_ulc_cfg.clear();
445  g_pub_twist.publish(twist_cmd);
446  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
447  EXPECT_FALSE(waitForMsg(ros::WallDuration(0.5), g_msg_ulc_cfg));
448  EXPECT_EQ((int16_t)(twist_cmd.linear.x / LIN_VEL_SCALE_FACTOR), g_msg_ulc_cmd.get().linear_velocity);
449  EXPECT_EQ((int16_t)(twist_cmd.angular.z / YAW_RATE_SCALE_FACTOR), g_msg_ulc_cmd.get().yaw_command);
450  EXPECT_EQ(0, g_msg_ulc_cmd.get().steering_mode);
451 
452  geometry_msgs::TwistStamped twist_stamped_cmd;
453  twist_stamped_cmd.twist = twist_cmd;
454  g_msg_ulc_cmd.clear();
455  g_msg_ulc_cfg.clear();
456  g_pub_twist_stamped.publish(twist_stamped_cmd);
457  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
458  EXPECT_FALSE(waitForMsg(ros::WallDuration(0.5), g_msg_ulc_cfg));
459  EXPECT_EQ((int16_t)(twist_cmd.linear.x / LIN_VEL_SCALE_FACTOR), g_msg_ulc_cmd.get().linear_velocity);
460  EXPECT_EQ((int16_t)(twist_cmd.angular.z / YAW_RATE_SCALE_FACTOR), g_msg_ulc_cmd.get().yaw_command);
461  EXPECT_EQ(0, g_msg_ulc_cmd.get().steering_mode);
462 }
463 
464 TEST(ULCNode, reportParsing)
465 {
466  can_msgs::Frame report_out;
467  report_out.id = ID_ULC_REPORT;
468  report_out.is_extended = false;
469  report_out.dlc = sizeof(MsgUlcReport);
470  MsgUlcReport* msg_report_ptr = (MsgUlcReport*)report_out.data.elems;
471  memset(msg_report_ptr, 0x00, sizeof(MsgUlcReport));
472  msg_report_ptr->timeout = false;
473  msg_report_ptr->tracking_mode = 0;
474  msg_report_ptr->steering_mode = 1;
475  msg_report_ptr->steering_enabled = false;
476  msg_report_ptr->pedals_enabled = true;
477  msg_report_ptr->speed_ref = 22.2f / SPEED_REPORT_SCALE_FACTOR;
478  msg_report_ptr->accel_ref = 1.1f / ACCEL_REPORT_SCALE_FACTOR;
479  msg_report_ptr->speed_meas = 21.1f / SPEED_REPORT_SCALE_FACTOR;
480  msg_report_ptr->accel_meas = 0.99f / ACCEL_REPORT_SCALE_FACTOR;
481  msg_report_ptr->max_steering_vel = 16.0f / MAX_RATE_SCALE_FACTOR;
482  msg_report_ptr->max_steering_angle = 55.0f / MAX_ANGLE_SCALE_FACTOR;
483  msg_report_ptr->speed_preempted = true;
484  msg_report_ptr->steering_preempted = false;
485  msg_report_ptr->override = true;
486 
487  g_pub_can.publish(report_out);
488  ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_report));
489  ASSERT_FALSE(g_msg_ulc_report.get().timeout);
490  ASSERT_EQ(0, g_msg_ulc_report.get().tracking_mode);
491  ASSERT_EQ(1, g_msg_ulc_report.get().steering_mode);
492  ASSERT_FALSE(g_msg_ulc_report.get().steering_enabled);
493  ASSERT_TRUE(g_msg_ulc_report.get().pedals_enabled);
494  ASSERT_FLOAT_EQ(22.2f, g_msg_ulc_report.get().speed_ref);
495  ASSERT_FLOAT_EQ(1.1f, g_msg_ulc_report.get().accel_ref);
496  ASSERT_FLOAT_EQ(21.1f, g_msg_ulc_report.get().speed_meas);
497  ASSERT_FLOAT_EQ(0.95f, g_msg_ulc_report.get().accel_meas);
498  ASSERT_FLOAT_EQ(16.0f, g_msg_ulc_report.get().max_steering_vel);
499  ASSERT_FLOAT_EQ(55.0f, g_msg_ulc_report.get().max_steering_angle);
500  ASSERT_TRUE(g_msg_ulc_report.get().speed_preempted);
501  ASSERT_FALSE(g_msg_ulc_report.get().steering_preempted);
502 
503 }
504 
505 int main(int argc, char **argv) {
506  testing::InitGoogleTest(&argc, argv);
507  ros::init(argc, argv, "ulc_node_test");
508  n = new ros::NodeHandle();
509  pn = new ros::NodeHandle("~");
510 
512  g_sub_can = n->subscribe("can_tx", 100, recvCan, NODELAY);
513  g_sub_report = n->subscribe("ulc_report", 10, recvReport, NODELAY);
514  g_pub_ulc_cmd = n->advertise<dataspeed_ulc_msgs::UlcCmd>("ulc_cmd", 2);
515  g_pub_enable = n->advertise<std_msgs::Bool>("dbw_enabled", 2);
516  g_pub_twist = n->advertise<geometry_msgs::Twist>("cmd_vel", 2);
517  g_pub_twist_stamped = n->advertise<geometry_msgs::TwistStamped>("cmd_vel_stamped", 2);
518  g_pub_can = n->advertise<can_msgs::Frame>("can_rx", 100);
519  pn->param("config_frequency", g_cfg_freq, 5.0);
520 
521  // Setup Spinner
522  ros::AsyncSpinner spinner(3);
523  spinner.start();
524 
525  // Run all the tests that were declared with TEST()
526  int result = RUN_ALL_TESTS();
527 
528  // Cleanup
529  spinner.stop();
530  n->shutdown();
531  pn->shutdown();
532 
533  // Return test result
534  return result;
535 }
double g_cfg_freq
ros::Publisher g_pub_enable
void publish(const boost::shared_ptr< M > &message) const
f
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber g_sub_can
ros::NodeHandle * n
ros::NodeHandle * pn
const double ANGULAR_ACCEL_SCALE_FACTOR
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
MsgRx< MsgUlcCfg > g_msg_ulc_cfg(ros::WallDuration(0.05))
const double ACCEL_REPORT_SCALE_FACTOR
bool fresh(ros::WallDuration delta) const
Definition: MsgRx.h:28
static bool waitForTopics(ros::WallDuration dur)
const double MAX_RATE_SCALE_FACTOR
TransportHints & tcpNoDelay(bool nodelay=true)
const double MAX_ANGLE_SCALE_FACTOR
int main(int argc, char **argv)
bool sleep() const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
uint32_t getNumPublishers() const
Definition: MsgRx.h:22
static bool waitForMsg(ros::WallDuration dur, const MsgRx< T > &msg_rx)
ros::Publisher g_pub_can
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void recvReport(const dataspeed_ulc_msgs::UlcReportConstPtr &msg)
const double LIN_VEL_SCALE_FACTOR
static void checkImmediateCfg()
ros::Publisher g_pub_twist
ros::Subscriber g_sub_report
MsgRx< dataspeed_ulc_msgs::UlcReport > g_msg_ulc_report(ros::WallDuration(0.05))
TEST(ULCNode, topics)
const double CURVATURE_SCALE_FACTOR
uint32_t getNumSubscribers() const
static WallTime now()
const double LATERAL_ACCEL_SCALE_FACTOR
const double LINEAR_ACCEL_SCALE_FACTOR
const double SPEED_REPORT_SCALE_FACTOR
const double LINEAR_DECEL_SCALE_FACTOR
ros::Publisher g_pub_twist_stamped
ros::Publisher g_pub_ulc_cmd
MsgRx< MsgUlcCmd > g_msg_ulc_cmd(ros::WallDuration(0.05))
dataspeed_ulc_msgs::UlcCmd g_ulc_cmd
const double YAW_RATE_SCALE_FACTOR
static void dispatchAssertSizes()
Definition: dispatch.h:90
void recvCan(const can_msgs::FrameConstPtr &msg)


dataspeed_ulc_can
Author(s): Micho Radovnikovich
autogenerated on Thu Jul 9 2020 03:45:43