test_ulc_node.cpp
Go to the documentation of this file.
00001 #include <gtest/gtest.h>
00002 #include <ros/ros.h>
00003 
00004 #include <std_msgs/Bool.h>
00005 #include <geometry_msgs/TwistStamped.h>
00006 #include <dataspeed_ulc_msgs/UlcCmd.h>
00007 #include <dataspeed_ulc_msgs/UlcReport.h>
00008 #include <dataspeed_ulc_can/dispatch.h>
00009 #include <can_msgs/Frame.h>
00010 #include "MsgRx.h"
00011 
00012 using namespace dataspeed_ulc_can;
00013 
00014 ros::NodeHandle *n, *pn;
00015 
00016 MsgRx<MsgUlcCmd> g_msg_ulc_cmd(ros::WallDuration(0.05));
00017 MsgRx<MsgUlcCfg> g_msg_ulc_cfg(ros::WallDuration(0.05));
00018 MsgRx<dataspeed_ulc_msgs::UlcReport> g_msg_ulc_report(ros::WallDuration(0.05));
00019 
00020 dataspeed_ulc_msgs::UlcCmd g_ulc_cmd;
00021 double g_cfg_freq;
00022 
00023 // Command message scale factors
00024 const double LIN_VEL_SCALE_FACTOR = 0.0025;
00025 const double YAW_RATE_SCALE_FACTOR = 0.00025;
00026 const double CURVATURE_SCALE_FACTOR = 0.0000061;
00027 
00028 // Config message scale factors
00029 const double LINEAR_ACCEL_SCALE_FACTOR = 0.02;
00030 const double LINEAR_DECEL_SCALE_FACTOR = 0.02;
00031 const double LATERAL_ACCEL_SCALE_FACTOR = 0.05;
00032 const double ANGULAR_ACCEL_SCALE_FACTOR = 0.02;
00033 
00034 // Report message scale factors
00035 const double SPEED_REPORT_SCALE_FACTOR = 0.02;
00036 const double ACCEL_REPORT_SCALE_FACTOR = 0.05;
00037 const double MAX_ANGLE_SCALE_FACTOR = 5.0;
00038 const double MAX_RATE_SCALE_FACTOR = 8.0;
00039 
00040 ros::Publisher g_pub_ulc_cmd;
00041 ros::Publisher g_pub_enable;
00042 ros::Publisher g_pub_twist;
00043 ros::Publisher g_pub_twist_stamped;
00044 ros::Publisher g_pub_can;
00045 ros::Subscriber g_sub_can;
00046 ros::Subscriber g_sub_report;
00047 
00048 void recvCan(const can_msgs::FrameConstPtr& msg)
00049 {
00050   if (!msg->is_rtr && !msg->is_error && !msg->is_extended) {
00051     switch (msg->id) {
00052       case ID_ULC_CMD:
00053         g_msg_ulc_cmd.set(*((MsgUlcCmd*)msg->data.elems));
00054         break;
00055       case ID_ULC_CONFIG:
00056         g_msg_ulc_cfg.set(*((MsgUlcCfg*)msg->data.elems));
00057         break;
00058     }
00059   }
00060 }
00061 
00062 void recvReport(const dataspeed_ulc_msgs::UlcReportConstPtr& msg)
00063 {
00064   g_msg_ulc_report.set(*msg);
00065 }
00066 
00067 template <class T>
00068 static bool waitForMsg(ros::WallDuration dur, const MsgRx<T>& msg_rx)
00069 {
00070   const ros::WallTime start = ros::WallTime::now();
00071   while (true) {
00072     if (msg_rx.fresh()) {
00073       return true;
00074     }
00075     if ((ros::WallTime::now() - start) > dur) {
00076       return false;
00077     }
00078     ros::WallDuration(0.001).sleep();
00079   }
00080 }
00081 
00082 static bool waitForTopics(ros::WallDuration dur) {
00083   const ros::WallTime start = ros::WallTime::now();
00084   while (true) {
00085     if ((g_sub_can.getNumPublishers() == 1)
00086      && (g_sub_report.getNumPublishers() == 1)
00087      && (g_pub_ulc_cmd.getNumSubscribers() == 1)
00088      && (g_pub_enable.getNumSubscribers() == 1)
00089      && (g_pub_twist.getNumSubscribers() == 1)
00090      && (g_pub_twist_stamped.getNumSubscribers() == 1)
00091      && (g_pub_can.getNumSubscribers() == 1)) {
00092       return true;
00093     }
00094     if ((ros::WallTime::now() - start) > dur) {
00095       return false;
00096     }
00097     ros::WallDuration(0.001).sleep();
00098   }
00099 }
00100 
00101 static void checkImmediateCfg()
00102 {
00103   ros::WallTime stamp = ros::WallTime::now();
00104   g_msg_ulc_cfg.clear();
00105   g_pub_ulc_cmd.publish(g_ulc_cmd);
00106   EXPECT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cfg));
00107   EXPECT_NEAR(g_msg_ulc_cfg.stamp().toSec(), stamp.toSec(), 0.01);
00108 }
00109 
00110 TEST(ULCNode, topics)
00111 {
00112   // Wait for all topics to connect before running other tests
00113   ASSERT_TRUE(waitForTopics(ros::WallDuration(2.0)));
00114   ros::WallDuration(1.0).sleep();
00115 
00116   // Call unused function to complete coverage testing
00117   dispatchAssertSizes();
00118 }
00119 
00120 TEST(ULCNode, cfgTiming)
00121 {
00122   g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
00123   g_ulc_cmd.linear_accel = 1.0;
00124   g_ulc_cmd.linear_decel = 1.0;
00125   g_ulc_cmd.lateral_accel = 1.0;
00126   g_ulc_cmd.angular_accel = 1.0;
00127 
00128   // Publish command messages with the same acceleration limits and make sure
00129   // config CAN messages are sent at the nominal rate
00130   size_t count = 0;
00131   ros::WallTime stamp_old;
00132   ros::WallTime t_end = ros::WallTime::now() + ros::WallDuration(1.0);
00133   g_msg_ulc_cfg.clear();
00134   while (t_end > ros::WallTime::now()) {
00135     g_pub_ulc_cmd.publish(g_ulc_cmd);
00136     ros::WallDuration(0.02).sleep();
00137     ros::WallTime stamp_new = g_msg_ulc_cfg.stamp();
00138     if (!stamp_new.isZero()) {
00139       if (!stamp_old.isZero() && (stamp_old != stamp_new)) {
00140         EXPECT_NEAR(stamp_old.toSec() + (1.0 / g_cfg_freq), stamp_new.toSec(), 0.01);
00141         count++;
00142       }
00143       stamp_old = stamp_new;
00144     }
00145   }
00146   EXPECT_GE(count, 1);
00147 
00148   // Change accel limits and make sure config CAN messages are sent immediately
00149   g_ulc_cmd.linear_accel = 2.0;
00150   checkImmediateCfg();
00151   g_ulc_cmd.linear_decel = 2.0;
00152   checkImmediateCfg();
00153   g_ulc_cmd.lateral_accel = 2.0;
00154   checkImmediateCfg();
00155   g_ulc_cmd.angular_accel = 2.0;
00156   checkImmediateCfg();
00157 }
00158 
00159 TEST(ULCNode, cmdRangeSaturation)
00160 {
00161   g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
00162 
00163   /*** Underflow tests ******************************************************/
00164   g_ulc_cmd.enable_pedals = true;
00165   g_ulc_cmd.enable_steering = true;
00166   g_ulc_cmd.linear_velocity = (INT16_MIN * LIN_VEL_SCALE_FACTOR) - 1.0;
00167   g_ulc_cmd.linear_accel = -1.0;
00168   g_ulc_cmd.linear_decel = -1.0;
00169   g_ulc_cmd.lateral_accel = -1.0;
00170   g_ulc_cmd.angular_accel = -1.0;
00171 
00172   // Yaw rate steering
00173   g_ulc_cmd.yaw_command = (INT16_MIN * YAW_RATE_SCALE_FACTOR) - 0.5;
00174   g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE;
00175   g_msg_ulc_cmd.clear();
00176   g_msg_ulc_cfg.clear();
00177   g_pub_ulc_cmd.publish(g_ulc_cmd);
00178   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00179   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cfg));
00180   EXPECT_EQ(INT16_MIN, g_msg_ulc_cmd.get().linear_velocity);
00181   EXPECT_EQ(INT16_MIN, g_msg_ulc_cmd.get().yaw_command);
00182   EXPECT_EQ(0, g_msg_ulc_cfg.get().linear_accel);
00183   EXPECT_EQ(0, g_msg_ulc_cfg.get().linear_decel);
00184   EXPECT_EQ(0, g_msg_ulc_cfg.get().lateral_accel);
00185   EXPECT_EQ(0, g_msg_ulc_cfg.get().angular_accel);
00186 
00187   // Curvature steering
00188   g_ulc_cmd.yaw_command = (INT16_MIN * CURVATURE_SCALE_FACTOR) - 0.05;
00189   g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::CURVATURE_MODE;
00190   g_msg_ulc_cmd.clear();
00191   g_msg_ulc_cfg.clear();
00192   g_pub_ulc_cmd.publish(g_ulc_cmd);
00193   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00194   EXPECT_EQ(INT16_MIN, g_msg_ulc_cmd.get().yaw_command);
00195   /**************************************************************************/
00196 
00197   /*** Overflow tests *******************************************************/
00198   g_ulc_cmd.enable_pedals = true;
00199   g_ulc_cmd.enable_steering = true;
00200   g_ulc_cmd.linear_velocity = (INT16_MAX * LIN_VEL_SCALE_FACTOR) + 1.0;
00201   g_ulc_cmd.linear_accel = 100.0;
00202   g_ulc_cmd.linear_decel = 100.0;
00203   g_ulc_cmd.lateral_accel = 100.0;
00204   g_ulc_cmd.angular_accel = 100.0;
00205 
00206   // Yaw rate steering
00207   g_ulc_cmd.yaw_command = (INT16_MAX * YAW_RATE_SCALE_FACTOR) + 0.5;
00208   g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE;
00209   g_msg_ulc_cmd.clear();
00210   g_msg_ulc_cfg.clear();
00211   g_pub_ulc_cmd.publish(g_ulc_cmd);
00212   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00213   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cfg));
00214   EXPECT_EQ(INT16_MAX, g_msg_ulc_cmd.get().linear_velocity);
00215   EXPECT_EQ(INT16_MAX, g_msg_ulc_cmd.get().yaw_command);
00216   EXPECT_EQ(UINT8_MAX, g_msg_ulc_cfg.get().linear_accel);
00217   EXPECT_EQ(UINT8_MAX, g_msg_ulc_cfg.get().linear_decel);
00218   EXPECT_EQ(UINT8_MAX, g_msg_ulc_cfg.get().lateral_accel);
00219   EXPECT_EQ(UINT8_MAX, g_msg_ulc_cfg.get().angular_accel);
00220 
00221   // Curvature steering
00222   g_ulc_cmd.yaw_command = (INT16_MAX * CURVATURE_SCALE_FACTOR) + 0.05;
00223   g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::CURVATURE_MODE;
00224   g_msg_ulc_cmd.clear();
00225   g_msg_ulc_cfg.clear();
00226   g_pub_ulc_cmd.publish(g_ulc_cmd);
00227   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00228   EXPECT_EQ(INT16_MAX, g_msg_ulc_cmd.get().yaw_command);
00229   /**************************************************************************/
00230 
00231   /*** +Inf tests ***********************************************************/
00232   g_ulc_cmd.enable_pedals = true;
00233   g_ulc_cmd.enable_steering = true;
00234   g_ulc_cmd.linear_velocity = INFINITY;
00235   g_ulc_cmd.linear_accel = INFINITY;
00236   g_ulc_cmd.linear_decel = INFINITY;
00237   g_ulc_cmd.lateral_accel = INFINITY;
00238   g_ulc_cmd.angular_accel = INFINITY;
00239 
00240   // Yaw rate steering
00241   g_ulc_cmd.yaw_command = INFINITY;
00242   g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE;
00243   g_msg_ulc_cmd.clear();
00244   g_msg_ulc_cfg.clear();
00245   g_pub_ulc_cmd.publish(g_ulc_cmd);
00246   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00247   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cfg));
00248   EXPECT_EQ(INT16_MAX, g_msg_ulc_cmd.get().linear_velocity);
00249   EXPECT_EQ(INT16_MAX, g_msg_ulc_cmd.get().yaw_command);
00250   EXPECT_EQ(UINT8_MAX, g_msg_ulc_cfg.get().linear_accel);
00251   EXPECT_EQ(UINT8_MAX, g_msg_ulc_cfg.get().linear_decel);
00252   EXPECT_EQ(UINT8_MAX, g_msg_ulc_cfg.get().lateral_accel);
00253   EXPECT_EQ(UINT8_MAX, g_msg_ulc_cfg.get().angular_accel);
00254 
00255   // Curvature steering
00256   g_ulc_cmd.yaw_command = INFINITY;
00257   g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::CURVATURE_MODE;
00258   g_msg_ulc_cmd.clear();
00259   g_msg_ulc_cfg.clear();
00260   g_pub_ulc_cmd.publish(g_ulc_cmd);
00261   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00262   EXPECT_EQ(INT16_MAX, g_msg_ulc_cmd.get().yaw_command);
00263   /**************************************************************************/
00264 
00265   /*** -Inf tests ***********************************************************/
00266   g_ulc_cmd.enable_pedals = true;
00267   g_ulc_cmd.enable_steering = true;
00268   g_ulc_cmd.linear_velocity = -INFINITY;
00269   g_ulc_cmd.linear_accel = -INFINITY;
00270   g_ulc_cmd.linear_decel = -INFINITY;
00271   g_ulc_cmd.lateral_accel = -INFINITY;
00272   g_ulc_cmd.angular_accel = -INFINITY;
00273 
00274   // Yaw rate steering
00275   g_ulc_cmd.yaw_command = -INFINITY;
00276   g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE;
00277   g_msg_ulc_cmd.clear();
00278   g_msg_ulc_cfg.clear();
00279   g_pub_ulc_cmd.publish(g_ulc_cmd);
00280   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00281   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cfg));
00282   EXPECT_EQ(INT16_MIN, g_msg_ulc_cmd.get().linear_velocity);
00283   EXPECT_EQ(INT16_MIN, g_msg_ulc_cmd.get().yaw_command);
00284   EXPECT_EQ(0, g_msg_ulc_cfg.get().linear_accel);
00285   EXPECT_EQ(0, g_msg_ulc_cfg.get().linear_decel);
00286   EXPECT_EQ(0, g_msg_ulc_cfg.get().lateral_accel);
00287   EXPECT_EQ(0, g_msg_ulc_cfg.get().angular_accel);
00288 
00289   // Curvature steering
00290   g_ulc_cmd.yaw_command = -INFINITY;
00291   g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::CURVATURE_MODE;
00292   g_msg_ulc_cmd.clear();
00293   g_msg_ulc_cfg.clear();
00294   g_pub_ulc_cmd.publish(g_ulc_cmd);
00295   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00296   EXPECT_EQ(INT16_MIN, g_msg_ulc_cmd.get().yaw_command);
00297   /**************************************************************************/
00298 }
00299 
00300 TEST(ULCNode, outOfBoundsInputs)
00301 {
00302   g_msg_ulc_cfg.clear();
00303 
00304   // NaN in linear velocity field
00305   g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
00306   g_ulc_cmd.linear_velocity = NAN;
00307   g_msg_ulc_cmd.clear();
00308   g_pub_ulc_cmd.publish(g_ulc_cmd);
00309   EXPECT_FALSE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00310 
00311   // NaN in yaw command field
00312   g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
00313   g_ulc_cmd.yaw_command = NAN;
00314   g_msg_ulc_cmd.clear();
00315   g_pub_ulc_cmd.publish(g_ulc_cmd);
00316   ASSERT_FALSE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00317 
00318   // NaN in linear accel field
00319   g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
00320   g_ulc_cmd.linear_accel = NAN;
00321   g_msg_ulc_cmd.clear();
00322   g_pub_ulc_cmd.publish(g_ulc_cmd);
00323   EXPECT_FALSE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00324 
00325   // NaN in linear decel field
00326   g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
00327   g_ulc_cmd.linear_decel = NAN;
00328   g_msg_ulc_cmd.clear();
00329   g_pub_ulc_cmd.publish(g_ulc_cmd);
00330   EXPECT_FALSE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00331 
00332   // NaN in lateral accel field
00333   g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
00334   g_ulc_cmd.lateral_accel = NAN;
00335   g_msg_ulc_cmd.clear();
00336   g_pub_ulc_cmd.publish(g_ulc_cmd);
00337   EXPECT_FALSE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00338 
00339   // NaN in angular accel field
00340   g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
00341   g_ulc_cmd.angular_accel = NAN;
00342   g_msg_ulc_cmd.clear();
00343   g_pub_ulc_cmd.publish(g_ulc_cmd);
00344   EXPECT_FALSE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00345 
00346   // Invalid steering mode
00347   g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
00348   g_ulc_cmd.steering_mode = 3;
00349   g_msg_ulc_cmd.clear();
00350   g_pub_ulc_cmd.publish(g_ulc_cmd);
00351   EXPECT_FALSE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00352 
00353   // Make sure no config messages were sent during this process
00354   EXPECT_FALSE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cfg));
00355 }
00356 
00357 TEST(ULCNode, scaleFactors)
00358 {
00359   g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
00360   g_ulc_cmd.linear_velocity = 22.3;
00361   g_ulc_cmd.linear_accel = 1.23;
00362   g_ulc_cmd.linear_decel = 3.45;
00363   g_ulc_cmd.lateral_accel = 5.43;
00364   g_ulc_cmd.angular_accel = 3.21;
00365 
00366   // Yaw rate steering
00367   g_ulc_cmd.yaw_command = 0.567;
00368   g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE;
00369   g_msg_ulc_cmd.clear();
00370   g_msg_ulc_cfg.clear();
00371   g_pub_ulc_cmd.publish(g_ulc_cmd);
00372   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00373   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cfg));
00374   EXPECT_EQ((int16_t)(g_ulc_cmd.linear_velocity / LIN_VEL_SCALE_FACTOR), g_msg_ulc_cmd.get().linear_velocity);
00375   EXPECT_EQ((int16_t)(g_ulc_cmd.yaw_command / YAW_RATE_SCALE_FACTOR), g_msg_ulc_cmd.get().yaw_command);
00376   EXPECT_EQ((int16_t)(g_ulc_cmd.linear_accel / LINEAR_ACCEL_SCALE_FACTOR), g_msg_ulc_cfg.get().linear_accel);
00377   EXPECT_EQ((int16_t)(g_ulc_cmd.linear_decel / LINEAR_DECEL_SCALE_FACTOR), g_msg_ulc_cfg.get().linear_decel);
00378   EXPECT_EQ((int16_t)(g_ulc_cmd.lateral_accel / LATERAL_ACCEL_SCALE_FACTOR), g_msg_ulc_cfg.get().lateral_accel);
00379   EXPECT_EQ((int16_t)(g_ulc_cmd.angular_accel / ANGULAR_ACCEL_SCALE_FACTOR), g_msg_ulc_cfg.get().angular_accel);
00380 
00381   // Curvature steering
00382   g_ulc_cmd.yaw_command = 0.0789;
00383   g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::CURVATURE_MODE;
00384   g_msg_ulc_cmd.clear();
00385   g_pub_ulc_cmd.publish(g_ulc_cmd);
00386   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00387   EXPECT_EQ((int16_t)(g_ulc_cmd.yaw_command / CURVATURE_SCALE_FACTOR), g_msg_ulc_cmd.get().yaw_command);
00388 }
00389 
00390 TEST(ULCNode, dbwEnable)
00391 {
00392   std_msgs::Bool dbw_enabled_msg;
00393 
00394   g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
00395   g_ulc_cmd.enable_pedals = true;
00396   g_ulc_cmd.enable_steering = true;
00397   g_ulc_cmd.enable_shifting = true;
00398   g_ulc_cmd.shift_from_park = true;
00399 
00400   // Make sure CAN enable signals are false because dbw_enabled was not sent yet
00401   g_msg_ulc_cmd.clear();
00402   g_pub_ulc_cmd.publish(g_ulc_cmd);
00403   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00404   EXPECT_FALSE(g_msg_ulc_cmd.get().enable_pedals);
00405   EXPECT_FALSE(g_msg_ulc_cmd.get().enable_steering);
00406   EXPECT_FALSE(g_msg_ulc_cmd.get().enable_shifting);
00407   EXPECT_FALSE(g_msg_ulc_cmd.get().shift_from_park);
00408 
00409   // Publish dbw_enabled as true
00410   dbw_enabled_msg.data = true;
00411   g_pub_enable.publish(dbw_enabled_msg);
00412   ros::WallDuration(0.001).sleep();
00413 
00414   // Send command again and make sure CAN enable signals are true
00415   g_msg_ulc_cmd.clear();
00416   g_pub_ulc_cmd.publish(g_ulc_cmd);
00417   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00418   EXPECT_TRUE(g_msg_ulc_cmd.get().enable_pedals);
00419   EXPECT_TRUE(g_msg_ulc_cmd.get().enable_steering);
00420   EXPECT_TRUE(g_msg_ulc_cmd.get().enable_shifting);
00421   EXPECT_TRUE(g_msg_ulc_cmd.get().shift_from_park);
00422 
00423   // Publish dbw_enabled as false and make sure CAN enable signals are false
00424   dbw_enabled_msg.data = false;
00425   g_pub_enable.publish(dbw_enabled_msg);
00426   ros::WallDuration(0.05).sleep();
00427   g_msg_ulc_cmd.clear();
00428   g_pub_ulc_cmd.publish(g_ulc_cmd);
00429   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00430   ASSERT_FALSE(g_msg_ulc_cmd.get().enable_pedals);
00431   ASSERT_FALSE(g_msg_ulc_cmd.get().enable_steering);
00432   ASSERT_FALSE(g_msg_ulc_cmd.get().enable_shifting);
00433   ASSERT_FALSE(g_msg_ulc_cmd.get().shift_from_park);
00434 }
00435 
00436 TEST(ULCNode, twistInputs)
00437 {
00438   geometry_msgs::Twist twist_cmd;
00439   twist_cmd.linear.x = 22.0;
00440   twist_cmd.angular.z = 0.2;
00441   ros::WallDuration(1.0).sleep();
00442 
00443   g_msg_ulc_cmd.clear();
00444   g_msg_ulc_cfg.clear();
00445   g_pub_twist.publish(twist_cmd);
00446   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00447   EXPECT_FALSE(waitForMsg(ros::WallDuration(0.5), g_msg_ulc_cfg));
00448   EXPECT_EQ((int16_t)(twist_cmd.linear.x / LIN_VEL_SCALE_FACTOR), g_msg_ulc_cmd.get().linear_velocity);
00449   EXPECT_EQ((int16_t)(twist_cmd.angular.z / YAW_RATE_SCALE_FACTOR), g_msg_ulc_cmd.get().yaw_command);
00450   EXPECT_EQ(0, g_msg_ulc_cmd.get().steering_mode);
00451 
00452   geometry_msgs::TwistStamped twist_stamped_cmd;
00453   twist_stamped_cmd.twist = twist_cmd;
00454   g_msg_ulc_cmd.clear();
00455   g_msg_ulc_cfg.clear();
00456   g_pub_twist_stamped.publish(twist_stamped_cmd);
00457   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_cmd));
00458   EXPECT_FALSE(waitForMsg(ros::WallDuration(0.5), g_msg_ulc_cfg));
00459   EXPECT_EQ((int16_t)(twist_cmd.linear.x / LIN_VEL_SCALE_FACTOR), g_msg_ulc_cmd.get().linear_velocity);
00460   EXPECT_EQ((int16_t)(twist_cmd.angular.z / YAW_RATE_SCALE_FACTOR), g_msg_ulc_cmd.get().yaw_command);
00461   EXPECT_EQ(0, g_msg_ulc_cmd.get().steering_mode);
00462 }
00463 
00464 TEST(ULCNode, reportParsing)
00465 {
00466   can_msgs::Frame report_out;
00467   report_out.id = ID_ULC_REPORT;
00468   report_out.is_extended = false;
00469   report_out.dlc = sizeof(MsgUlcReport);
00470   MsgUlcReport* msg_report_ptr = (MsgUlcReport*)report_out.data.elems;
00471   memset(msg_report_ptr, 0x00, sizeof(MsgUlcReport));
00472   msg_report_ptr->timeout = false;
00473   msg_report_ptr->tracking_mode = 0;
00474   msg_report_ptr->steering_mode = 1;
00475   msg_report_ptr->steering_enabled = false;
00476   msg_report_ptr->pedals_enabled = true;
00477   msg_report_ptr->speed_ref = 22.2f / SPEED_REPORT_SCALE_FACTOR;
00478   msg_report_ptr->accel_ref = 1.1f / ACCEL_REPORT_SCALE_FACTOR;
00479   msg_report_ptr->speed_meas = 21.1f / SPEED_REPORT_SCALE_FACTOR;
00480   msg_report_ptr->accel_meas = 0.99f / ACCEL_REPORT_SCALE_FACTOR;
00481   msg_report_ptr->max_steering_vel = 16.0f / MAX_RATE_SCALE_FACTOR;
00482   msg_report_ptr->max_steering_angle = 55.0f / MAX_ANGLE_SCALE_FACTOR;
00483   msg_report_ptr->speed_preempted = true;
00484   msg_report_ptr->steering_preempted = false;
00485   msg_report_ptr->override = true;
00486 
00487   g_pub_can.publish(report_out);
00488   ASSERT_TRUE(waitForMsg(ros::WallDuration(0.1), g_msg_ulc_report));
00489   ASSERT_FALSE(g_msg_ulc_report.get().timeout);
00490   ASSERT_EQ(0, g_msg_ulc_report.get().tracking_mode);
00491   ASSERT_EQ(1, g_msg_ulc_report.get().steering_mode);
00492   ASSERT_FALSE(g_msg_ulc_report.get().steering_enabled);
00493   ASSERT_TRUE(g_msg_ulc_report.get().pedals_enabled);
00494   ASSERT_FLOAT_EQ(22.2f, g_msg_ulc_report.get().speed_ref);
00495   ASSERT_FLOAT_EQ(1.1f, g_msg_ulc_report.get().accel_ref);
00496   ASSERT_FLOAT_EQ(21.1f, g_msg_ulc_report.get().speed_meas);
00497   ASSERT_FLOAT_EQ(0.95f, g_msg_ulc_report.get().accel_meas);
00498   ASSERT_FLOAT_EQ(16.0f, g_msg_ulc_report.get().max_steering_vel);
00499   ASSERT_FLOAT_EQ(55.0f, g_msg_ulc_report.get().max_steering_angle);
00500   ASSERT_TRUE(g_msg_ulc_report.get().speed_preempted);
00501   ASSERT_FALSE(g_msg_ulc_report.get().steering_preempted);
00502 
00503 }
00504 
00505 int main(int argc, char **argv) {
00506   testing::InitGoogleTest(&argc, argv);
00507   ros::init(argc, argv, "ulc_node_test");
00508   n = new ros::NodeHandle();
00509   pn = new ros::NodeHandle("~");
00510 
00511   const ros::TransportHints NODELAY = ros::TransportHints().tcpNoDelay();
00512   g_sub_can = n->subscribe("can_tx", 100, recvCan, NODELAY);
00513   g_sub_report = n->subscribe("ulc_report", 10, recvReport, NODELAY);
00514   g_pub_ulc_cmd = n->advertise<dataspeed_ulc_msgs::UlcCmd>("ulc_cmd", 2);
00515   g_pub_enable = n->advertise<std_msgs::Bool>("dbw_enabled", 2);
00516   g_pub_twist = n->advertise<geometry_msgs::Twist>("cmd_vel", 2);
00517   g_pub_twist_stamped = n->advertise<geometry_msgs::TwistStamped>("cmd_vel_stamped", 2);
00518   g_pub_can = n->advertise<can_msgs::Frame>("can_rx", 100);
00519   pn->param("config_frequency", g_cfg_freq, 5.0);
00520 
00521   // Setup Spinner
00522   ros::AsyncSpinner spinner(3);
00523   spinner.start();
00524 
00525   // Run all the tests that were declared with TEST()
00526   int result = RUN_ALL_TESTS();
00527 
00528   // Cleanup
00529   spinner.stop();
00530   n->shutdown();
00531   pn->shutdown();
00532 
00533   // Return test result
00534   return result;
00535 }


dataspeed_ulc_can
Author(s): Micho Radovnikovich
autogenerated on Thu May 16 2019 03:04:21