#include <gtest/gtest.h>#include <ros/ros.h>#include <std_msgs/Bool.h>#include <geometry_msgs/TwistStamped.h>#include <dataspeed_ulc_msgs/UlcCmd.h>#include <dataspeed_ulc_msgs/UlcReport.h>#include <dataspeed_ulc_can/dispatch.h>#include <can_msgs/Frame.h>#include "MsgRx.h"
Go to the source code of this file.
Functions | |
| static void | checkImmediateCfg () |
| MsgRx< MsgUlcCfg > | g_msg_ulc_cfg (ros::WallDuration(0.05)) |
| MsgRx< MsgUlcCmd > | g_msg_ulc_cmd (ros::WallDuration(0.05)) |
| MsgRx < dataspeed_ulc_msgs::UlcReport > | g_msg_ulc_report (ros::WallDuration(0.05)) |
| int | main (int argc, char **argv) |
| void | recvCan (const can_msgs::FrameConstPtr &msg) |
| void | recvReport (const dataspeed_ulc_msgs::UlcReportConstPtr &msg) |
| TEST (ULCNode, topics) | |
| TEST (ULCNode, cfgTiming) | |
| TEST (ULCNode, cmdRangeSaturation) | |
| TEST (ULCNode, outOfBoundsInputs) | |
| TEST (ULCNode, scaleFactors) | |
| TEST (ULCNode, dbwEnable) | |
| TEST (ULCNode, twistInputs) | |
| TEST (ULCNode, reportParsing) | |
| template<class T > | |
| static bool | waitForMsg (ros::WallDuration dur, const MsgRx< T > &msg_rx) |
| static bool | waitForTopics (ros::WallDuration dur) |
Variables | |
| const double | ACCEL_REPORT_SCALE_FACTOR = 0.05 |
| const double | ANGULAR_ACCEL_SCALE_FACTOR = 0.02 |
| const double | CURVATURE_SCALE_FACTOR = 0.0000061 |
| double | g_cfg_freq |
| ros::Publisher | g_pub_can |
| ros::Publisher | g_pub_enable |
| ros::Publisher | g_pub_twist |
| ros::Publisher | g_pub_twist_stamped |
| ros::Publisher | g_pub_ulc_cmd |
| ros::Subscriber | g_sub_can |
| ros::Subscriber | g_sub_report |
| dataspeed_ulc_msgs::UlcCmd | g_ulc_cmd |
| const double | LATERAL_ACCEL_SCALE_FACTOR = 0.05 |
| const double | LIN_VEL_SCALE_FACTOR = 0.0025 |
| const double | LINEAR_ACCEL_SCALE_FACTOR = 0.02 |
| const double | LINEAR_DECEL_SCALE_FACTOR = 0.02 |
| const double | MAX_ANGLE_SCALE_FACTOR = 5.0 |
| const double | MAX_RATE_SCALE_FACTOR = 8.0 |
| ros::NodeHandle * | n |
| ros::NodeHandle * | pn |
| const double | SPEED_REPORT_SCALE_FACTOR = 0.02 |
| const double | YAW_RATE_SCALE_FACTOR = 0.00025 |
| static void checkImmediateCfg | ( | ) | [static] |
Definition at line 101 of file test_ulc_node.cpp.
| MsgRx<MsgUlcCfg> g_msg_ulc_cfg | ( | ros:: | WallDuration0.05 | ) |
| MsgRx<MsgUlcCmd> g_msg_ulc_cmd | ( | ros:: | WallDuration0.05 | ) |
| MsgRx<dataspeed_ulc_msgs::UlcReport> g_msg_ulc_report | ( | ros:: | WallDuration0.05 | ) |
| int main | ( | int | argc, |
| char ** | argv | ||
| ) |
Definition at line 505 of file test_ulc_node.cpp.
| void recvCan | ( | const can_msgs::FrameConstPtr & | msg | ) |
Definition at line 48 of file test_ulc_node.cpp.
| void recvReport | ( | const dataspeed_ulc_msgs::UlcReportConstPtr & | msg | ) |
Definition at line 62 of file test_ulc_node.cpp.
| TEST | ( | ULCNode | , |
| topics | |||
| ) |
Definition at line 110 of file test_ulc_node.cpp.
| TEST | ( | ULCNode | , |
| cfgTiming | |||
| ) |
Definition at line 120 of file test_ulc_node.cpp.
| TEST | ( | ULCNode | , |
| cmdRangeSaturation | |||
| ) |
Definition at line 159 of file test_ulc_node.cpp.
| TEST | ( | ULCNode | , |
| outOfBoundsInputs | |||
| ) |
Definition at line 300 of file test_ulc_node.cpp.
| TEST | ( | ULCNode | , |
| scaleFactors | |||
| ) |
Definition at line 357 of file test_ulc_node.cpp.
| TEST | ( | ULCNode | , |
| dbwEnable | |||
| ) |
Definition at line 390 of file test_ulc_node.cpp.
| TEST | ( | ULCNode | , |
| twistInputs | |||
| ) |
Definition at line 436 of file test_ulc_node.cpp.
| TEST | ( | ULCNode | , |
| reportParsing | |||
| ) |
Definition at line 464 of file test_ulc_node.cpp.
| static bool waitForMsg | ( | ros::WallDuration | dur, |
| const MsgRx< T > & | msg_rx | ||
| ) | [static] |
Definition at line 68 of file test_ulc_node.cpp.
| static bool waitForTopics | ( | ros::WallDuration | dur | ) | [static] |
Definition at line 82 of file test_ulc_node.cpp.
| const double ACCEL_REPORT_SCALE_FACTOR = 0.05 |
Definition at line 36 of file test_ulc_node.cpp.
| const double ANGULAR_ACCEL_SCALE_FACTOR = 0.02 |
Definition at line 32 of file test_ulc_node.cpp.
| const double CURVATURE_SCALE_FACTOR = 0.0000061 |
Definition at line 26 of file test_ulc_node.cpp.
| double g_cfg_freq |
Definition at line 21 of file test_ulc_node.cpp.
Definition at line 44 of file test_ulc_node.cpp.
Definition at line 41 of file test_ulc_node.cpp.
Definition at line 42 of file test_ulc_node.cpp.
Definition at line 43 of file test_ulc_node.cpp.
Definition at line 40 of file test_ulc_node.cpp.
Definition at line 45 of file test_ulc_node.cpp.
Definition at line 46 of file test_ulc_node.cpp.
| dataspeed_ulc_msgs::UlcCmd g_ulc_cmd |
Definition at line 20 of file test_ulc_node.cpp.
| const double LATERAL_ACCEL_SCALE_FACTOR = 0.05 |
Definition at line 31 of file test_ulc_node.cpp.
| const double LIN_VEL_SCALE_FACTOR = 0.0025 |
Definition at line 24 of file test_ulc_node.cpp.
| const double LINEAR_ACCEL_SCALE_FACTOR = 0.02 |
Definition at line 29 of file test_ulc_node.cpp.
| const double LINEAR_DECEL_SCALE_FACTOR = 0.02 |
Definition at line 30 of file test_ulc_node.cpp.
| const double MAX_ANGLE_SCALE_FACTOR = 5.0 |
Definition at line 37 of file test_ulc_node.cpp.
| const double MAX_RATE_SCALE_FACTOR = 8.0 |
Definition at line 38 of file test_ulc_node.cpp.
Definition at line 14 of file test_ulc_node.cpp.
Definition at line 14 of file test_ulc_node.cpp.
| const double SPEED_REPORT_SCALE_FACTOR = 0.02 |
Definition at line 35 of file test_ulc_node.cpp.
| const double YAW_RATE_SCALE_FACTOR = 0.00025 |
Definition at line 25 of file test_ulc_node.cpp.