1 #include <gtest/gtest.h> 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> 48 void recvCan(
const can_msgs::FrameConstPtr& msg)
50 if (!msg->is_rtr && !msg->is_error && !msg->is_extended) {
62 void recvReport(
const dataspeed_ulc_msgs::UlcReportConstPtr& msg)
105 g_pub_ulc_cmd.
publish(g_ulc_cmd);
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;
135 g_pub_ulc_cmd.
publish(g_ulc_cmd);
138 if (!stamp_new.
isZero()) {
139 if (!stamp_old.
isZero() && (stamp_old != stamp_new)) {
143 stamp_old = stamp_new;
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;
159 TEST(ULCNode, cmdRangeSaturation)
161 g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
164 g_ulc_cmd.enable_pedals =
true;
165 g_ulc_cmd.enable_steering =
true;
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;
174 g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE;
177 g_pub_ulc_cmd.
publish(g_ulc_cmd);
189 g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::CURVATURE_MODE;
192 g_pub_ulc_cmd.
publish(g_ulc_cmd);
198 g_ulc_cmd.enable_pedals =
true;
199 g_ulc_cmd.enable_steering =
true;
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;
208 g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE;
211 g_pub_ulc_cmd.
publish(g_ulc_cmd);
223 g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::CURVATURE_MODE;
226 g_pub_ulc_cmd.
publish(g_ulc_cmd);
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;
241 g_ulc_cmd.yaw_command = INFINITY;
242 g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE;
245 g_pub_ulc_cmd.
publish(g_ulc_cmd);
256 g_ulc_cmd.yaw_command = INFINITY;
257 g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::CURVATURE_MODE;
260 g_pub_ulc_cmd.
publish(g_ulc_cmd);
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;
275 g_ulc_cmd.yaw_command = -INFINITY;
276 g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE;
279 g_pub_ulc_cmd.
publish(g_ulc_cmd);
290 g_ulc_cmd.yaw_command = -INFINITY;
291 g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::CURVATURE_MODE;
294 g_pub_ulc_cmd.
publish(g_ulc_cmd);
300 TEST(ULCNode, outOfBoundsInputs)
305 g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
306 g_ulc_cmd.linear_velocity = NAN;
308 g_pub_ulc_cmd.
publish(g_ulc_cmd);
312 g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
313 g_ulc_cmd.yaw_command = NAN;
315 g_pub_ulc_cmd.
publish(g_ulc_cmd);
319 g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
320 g_ulc_cmd.linear_accel = NAN;
322 g_pub_ulc_cmd.
publish(g_ulc_cmd);
326 g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
327 g_ulc_cmd.linear_decel = NAN;
329 g_pub_ulc_cmd.
publish(g_ulc_cmd);
333 g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
334 g_ulc_cmd.lateral_accel = NAN;
336 g_pub_ulc_cmd.
publish(g_ulc_cmd);
340 g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
341 g_ulc_cmd.angular_accel = NAN;
343 g_pub_ulc_cmd.
publish(g_ulc_cmd);
347 g_ulc_cmd = dataspeed_ulc_msgs::UlcCmd();
348 g_ulc_cmd.steering_mode = 3;
350 g_pub_ulc_cmd.
publish(g_ulc_cmd);
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;
367 g_ulc_cmd.yaw_command = 0.567;
368 g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE;
371 g_pub_ulc_cmd.
publish(g_ulc_cmd);
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);
382 g_ulc_cmd.yaw_command = 0.0789;
383 g_ulc_cmd.steering_mode = dataspeed_ulc_msgs::UlcCmd::CURVATURE_MODE;
385 g_pub_ulc_cmd.
publish(g_ulc_cmd);
387 EXPECT_EQ((int16_t)(g_ulc_cmd.yaw_command / CURVATURE_SCALE_FACTOR),
g_msg_ulc_cmd.get().yaw_command);
392 std_msgs::Bool dbw_enabled_msg;
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;
402 g_pub_ulc_cmd.
publish(g_ulc_cmd);
410 dbw_enabled_msg.data =
true;
411 g_pub_enable.
publish(dbw_enabled_msg);
416 g_pub_ulc_cmd.
publish(g_ulc_cmd);
424 dbw_enabled_msg.data =
false;
425 g_pub_enable.
publish(dbw_enabled_msg);
428 g_pub_ulc_cmd.
publish(g_ulc_cmd);
438 geometry_msgs::Twist twist_cmd;
439 twist_cmd.linear.x = 22.0;
440 twist_cmd.angular.z = 0.2;
445 g_pub_twist.
publish(twist_cmd);
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);
452 geometry_msgs::TwistStamped twist_stamped_cmd;
453 twist_stamped_cmd.twist = twist_cmd;
456 g_pub_twist_stamped.
publish(twist_stamped_cmd);
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);
466 can_msgs::Frame report_out;
468 report_out.is_extended =
false;
472 msg_report_ptr->
timeout =
false;
505 int main(
int argc,
char **argv) {
506 testing::InitGoogleTest(&argc, argv);
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);
526 int result = RUN_ALL_TESTS();
ros::Publisher g_pub_enable
void publish(const boost::shared_ptr< M > &message) const
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
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
static bool waitForTopics(ros::WallDuration dur)
const double MAX_RATE_SCALE_FACTOR
uint16_t steering_enabled
TransportHints & tcpNoDelay(bool nodelay=true)
const double MAX_ANGLE_SCALE_FACTOR
int main(int argc, char **argv)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
uint32_t getNumPublishers() const
static bool waitForMsg(ros::WallDuration dur, const MsgRx< T > &msg_rx)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint8_t steering_preempted
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))
const double CURVATURE_SCALE_FACTOR
uint32_t getNumSubscribers() const
uint8_t max_steering_angle
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()
void recvCan(const can_msgs::FrameConstPtr &msg)