2.4.3.3. Utilities ROS Package

2.4.3.3.1. utilities

Package holding launch files and messages used in the whole AS

Maintainers:
Version:

2.0.0

License:

TODO

2.4.3.3.1.1. Dependencies

Build:
  • roscpp

  • rospy

  • message_generation

  • std_msgs

  • geometry_msgs

  • sensor_msgs

Build export:
  • roscpp

  • rospy

Build tool:

catkin

Execution:
  • roscpp

  • rospy

  • message_runtime

  • std_msgs

  • sensor_msgs

  • geometry_msgs

2.4.3.3.1.2. Messages

message utilities/BoundingBox
Parameters:
  • probability (float64) – Probability that the perceived cone is of this color.

  • id (int16) – ID (color) of the perceived cone. 0: yellow, 1: blue, 2: small orange, 3: big orange.

  • used_mask (bool) – Whether the mask of the cone was used to determine the cone top

  • x_cone_top (int16) – x point of top of the perceived cone mask

  • y_cone_top (int16) – y point of top of the perceived cone mask

  • xmin (int64) – X coordinate of the upper left corner of the bounding box.

  • ymin (int64) – Y coordinate of the upper left corner of the bounding box.

  • xmax (int64) – X coordinate of the lower right corner of the bounding box.

  • ymax (int64) – Y coordinate of the lower right corner of the bounding box.

  • Class (string) – String representation of the color of the perceived cone.

  • mask (sensor_msgs/Image) – Mask of the perceived cone.

Message containing a bounding box for a perceived cone in an image.

message utilities/ConePosition
Parameters:
  • x (float64) – X position of the cone.

  • y (float64) – Y position of the cone.

  • id (int16) – ID (color) of the cone.

  • probability (float64) – Probability that the cone is of this color.

  • is_lidar (bool) – LiDAR was used to determine position

Message containing a position, id and probability for a cone.

message utilities/CalibrationMatrices
Parameters:
  • extrinsic_matrix_left (float64[]) – extrinsic matrix of left camera

  • extrinsic_matrix_right (float64[]) – extrinsic matrix of right camera

  • intrinsic_matrix_left (float64[]) – intrinsic matrix of left camera

  • intrinsic_matrix_right (float64[]) – intrinsic matrix of right camera

  • extrinsic_matrix_lidar_to_camera (float64[]) – extrinsic matrix of LiDAR to camera

message containing the calibration matrices used during the run.

message utilities/TrajectoryPathSlices
Parameters:
  • header (Header) – Header containing the time the trajectory has been calculated at.

  • image_header (Header) – Header of the image the centerpoints are based on.

  • pose_header (Header) – Header of the vehicle pose the trajectory has been calculated for.

  • path_slices (utilities/TrajectoryPathSlice[]) – List of x coordinates of path.

Message containing a possible path slices for a trajectory.

message utilities/ConePositionWithCovariance
Parameters:
  • x (float64) – X position of the cone.

  • y (float64) – Y position of the cone.

  • id (int16) – ID (color) of the cone.

  • perceived_n (uint16) – Number of times the cone has already been perceived

  • covariance (float64[4]) – Position covariance of the cone.

Message containing a position, id and position covariance for a cone.

message utilities/TrajectoryPathSlice
Parameters:
  • x (float64[]) – List of x coordinates of path.

  • y (float64[]) – List of y coordinates of path.

  • average_squared_curvature_cost (float64) – Relative cost of average squared curvature of path

  • peak_squared_curvature_cost (float64) – Relative cost of peak squared curvature of path

  • length_cost (float64) – Relative cost of length of path

  • total_cost (float64) – Relative total cost of path

Message containing a possible path slice for a trajectory.

message utilities/ConeListWithCovariance
Parameters:
  • header (Header) – Header containing the latest image header the cones are based on.

  • cones (utilities/ConePositionWithCovariance[]) – List of cones with position, color and covariance.

  • closed_track (bool) – Flag whether the tracked landmarks form a closed track.

Message containing a list of cone positions, colors and covariance.

message utilities/DisablePerception
Parameters:
  • header (Header) – Header containing the time the message has been created at.

  • disable_perception (bool) – Flag to indicate whether the perception should be enabled or disabled.

Message containing flag to disable the perception when not needed anymore for SLAM.

message utilities/BoundingBoxes
Parameters:
  • header (Header) – Header containing the time the bounding boxes have been calculated at.

  • image_header (Header) – Header of the processed image containing the time the image has been recorded at.

  • lidar_header (Header) – Header of the lidar pointcloud to match with the image.

  • processing_time (float64) – Processing time for one image

  • bounding_boxes (utilities/BoundingBox[]) – Bounding boxes perceived in the image.

Message containing all bounding boxes for an processed image by the trt inference.

message utilities/MapAlignment
Parameters:
  • header (Header) – Header containing the latest image header the cone informations are based on.

  • observable_preloaded_cones (utilities/ConePositionWithCovariance[]) – Observable share of preloaded cones for calculating mapping for alignment.

  • tracked_observed_cones (utilities/ConePosition[]) – Tracked cones of SLAM based on really observed cones.

  • mapping (int16[]) – Mapping between observed landmarks and observable landmarks

  • individual_compatibility (bool[]) – Compatibility between observed and observable landmarks (observable x observed)

  • translation (float64[2]) – Translation of resulting map alignment (x, y).

  • rotation_matrix (float64[4]) – Rotation_matrix of resulting map alignment.

  • rotation_angle (float64) – Rotation angle [degree] of resulting map alignment.

  • weights (float64[]) – Weight of the map alignment.

  • tracked_landmarks_rectangle (float64[8]) – tracked_landmarks_rectangle

Message containing information for debugging and visualizing the map alignment of preloaded maps by SLAM.

message utilities/TrajectoryPoints
Parameters:
  • header (Header) – Header containing the time the trajectory has been calculated at.

  • image_header (Header) – Header of the image the centerpoints are based on.

  • pose_header (Header) – Header of the vehicle pose the trajectory has been calculated for.

  • x (float64[]) – X coordinate of the planned trajectory.

  • y (float64[]) – Y coordinate of the planned trajectory.

  • v (float64[]) – Velocity matching to the coordinates of the trajectory.

  • closed (bool) – Flag indicating whether the trajectory is closed.

  • lap_time (float64) – Lap time of the planned closed trajectory in seconds.

  • local_planning_calculation_time (float64) – Time the local motion planning needed for calculation in seconds.

  • global_planning_calculation_time (float64) – Time the global motion planning needed for calculation in seconds.

Message containing the planned trajectory.

message utilities/ConeList
Parameters:
  • header (Header) – Header containing the time the cone positions have been calculated at.

  • image_header (Header) – Header of the image the cones have been perceived in containing the time the image has been recorded at.

  • lidar_header (Header) – Header of the image the cones have been perceived in containing the time the image has been recorded at.

  • cones (utilities/ConePosition[]) – List of cone positions.

  • processing_time (float64) – Time needed for the calculation

  • lidar_processing_time (float64) – Time needed for the lidar transformation

  • sensor_time_delta (float64) – Time needed for the lidar transformation

Message containing a list of cone positions.

message utilities/PredictedMeasurements
Parameters:
  • header (Header) – Time the kalman filter has been executed for.

  • wheelspeed_fr (float64[3]) – Predicted measurement, true measurement and it’s uncertainty for the front right wheelspeed.

  • wheelspeed_fl (float64[3]) – Predicted measurement, true measurement and it’s uncertainty for the front left wheelspeed.

  • wheelspeed_rr (float64[3]) – Predicted measurement, true measurement and it’s uncertainty for the rear right wheelspeed.

  • wheelspeed_rl (float64[3]) – Predicted measurement, true measurement and it’s uncertainty for the rear left wheelspeed.

  • gps_heading (float64[3]) – Predicted measurement, true measurement and it’s uncertainty for the gps heading.

  • gps_speed (float64[3]) – Predicted measurement, true measurement and it’s uncertainty for the gps speed.

  • gps_x (float64[3]) – Predicted measurement, true measurement and it’s uncertainty for the gps x position.

  • gps_y (float64[3]) – Predicted measurement, true measurement and it’s uncertainty for the gps y position.

  • u (float64[3]) – Control input [Steering Wheel Angle, Acceration in x direction and gyro around z axis]

  • observed_landmarks (utilities/ConePosition[]) – List of true observed landmarks.

  • predicted_observed_landmarks (utilities/ConePosition[]) – List of predicted observed landmarks.

  • observable_landmarks (utilities/ConePosition[]) – List of observable landmarks.

  • mapping (int16[]) – Mapping between observed landmarks and mapped landmarks

  • individual_compatibility (bool[]) – Compatibility between observed and observable landmarks (observable x observed)

  • used_sensors (string[]) – List of used sensors during update step.

  • landmark_association_nodes_explored_n (uint32) – Number of explored nodes during landmark association

  • landmark_association_compared_associations_n (uint32) – Number of compared associations during landmark association

  • cluster_sizes (uint16[]) – Number of landmarks in each cluster

  • execution_time (float64) – Time it took to execute the kalman filter

  • local_msg_usage_delay (float64) – Time it took from arrival of LocalMapping message until it was used

  • update_unscented_transform_time_lm (float64) – Time it took to execute the corresponding functions in seconds

  • update_calculate_sigma_f_points_time_lm (float64) – Time it took to execute the corresponding functions in seconds

  • data_association_time (float64) – Time it took to execute the corresponding functions in seconds

Message used to debug the SLAM algorithm regarding the predicted and true measurements and their uncertainty.

message utilities/CenterPoints
Parameters:
  • header (Header) – Header containing the time the centerpoints have been calculated at.

  • image_header (Header) – Header of the image the track is based on containing the time the image has been recorded at.

  • x (float64[]) – X coordinates of the computed centerpoints.

  • y (float64[]) – Y coordinates of the computed centerpoints.

  • left_track_width (float64[]) – Left track width of the computed centerpoints.

  • right_track_width (float64[]) – Right track width of the computed centerpoints.

  • closed_track (bool) – Flag whether the centerpoints form a closed track.

  • vehicle_pose (utilities/VehiclePose) – Vehicle pose for which the centerpoints have been computed for.

  • strategy (int32[]) – Strategy used to compute the centerpoints.

  • elapsed_time (float64) – Runtime of the centerpoint computation.

message containing the coordinates of the centerpoints of the perceived and filtered track and the matching right and left track width.

message utilities/MPCStatistics
Parameters:

Message containing the statistics for the solver statistics of the mpc for a prediction step

message utilities/PredictedStates
Parameters:
  • header (Header) – Header containing the time the predicted states have been calculated at.

  • pose_header (Header) – Header of the vehicle pose the predicted states has been calculated for.

  • image_header (Header) – Header of the image the trajectory has been calculated for.

  • t (float64[]) – Relative time of the predicted vehicle states.

  • x_pos (float64[]) – X coordinates of the predicted vehicle states.

  • y_pos (float64[]) – Y coordinates of the predicted vehicle states.

  • psi (float64[]) – Global heading of the predicted vehicle states.

  • v_x (float64[]) – Velocity in x-axis direction of the predicted vehicle states.

  • steering_wheel_angle (float64[]) – Steering wheel angle of the predicted vehicle states.

  • delta_rate (float64[]) – Ackermann rate of the predicted control inputs

  • a_x (float64[]) – Accelerations in x direction of the predicted control inputs

  • torque (float64[]) – Necessary motor torque request to reach the respective acceleration

  • service_brake_pressure (float64[]) – Necessary service brake pressure request to reach the respective acceleration

Message containing the predicted states of the model predictice controller of the control module.

message utilities/VehiclePose
Parameters:
  • header (Header) – Header containing the time the can message has been received at.

  • x (float64) – X coordinate of global vehicle position.

  • y (float64) – Y coordinate of global vehicle position.

  • v_x (float64) – Velocity in x-axis direction of vehicle.

  • psi (float64) – Global heading of vehicle.

  • P (float64[16]) – Covariance of the vehicle pose.

Message containing a vehicle pose: position, velocity and heading.

2.4.3.3.1.3. Package definition files

2.4.3.3.1.3.1. CMakeLists.txt

 1cmake_minimum_required(VERSION 3.0.0)
 2project(utilities VERSION 2.0.0)
 3
 4find_package(catkin REQUIRED COMPONENTS
 5  roscpp
 6  rospy
 7  message_generation
 8  std_msgs
 9  geometry_msgs
10        sensor_msgs
11)
12
13if(NOT CMAKE_BUILD_TYPE)
14 set(CMAKE_BUILD_TYPE Release)
15endif()
16
17# Set Flags for Debug and Release
18set(CMAKE_CXX_FLAGS_DEBUG "-g")
19set(CMAKE_CXX_FLAGS_RELEASE "-O3")
20
21## Generate messages in the 'msg' folder
22add_message_files(
23  FILES
24
25  # Perception Messages
26  BoundingBox.msg
27  BoundingBoxes.msg
28
29  # Mapping Messages
30  ConeList.msg
31  ConePosition.msg
32  CalibrationMatrices.msg
33
34  # Motion Planning Messages
35  TrajectoryPoints.msg
36  TrajectoryPathSlice.msg
37  TrajectoryPathSlices.msg
38
39  # SLAM Messages
40  VehiclePose.msg
41  ConeListWithCovariance.msg
42  ConePositionWithCovariance.msg
43  DisablePerception.msg
44  PredictedMeasurements.msg
45  MapAlignment.msg
46
47  # Filtering Messages
48  CenterPoints.msg
49
50  # Control Messages
51  PredictedStates.msg
52  MPCStatistics.msg
53)
54
55 generate_messages(
56   DEPENDENCIES
57   std_msgs
58   geometry_msgs
59         sensor_msgs
60 )
61
62catkin_package(
63  CATKIN_DEPENDS roscpp rospy message_runtime std_msgs geometry_msgs sensor_msgs
64)
65
66include_directories(
67  ${catkin_INCLUDE_DIRS}
68)

2.4.3.3.1.3.2. package.xml

 1<?xml version="1.0"?>
 2<package format="2">
 3  <name>utilities</name>
 4  <version>2.0.0</version>
 5  <description>Package holding launch files and messages used in the whole AS</description>
 6
 7  <maintainer email="martina.scheffler@curemannheim.de">Martina Scheffler</maintainer>
 8  <maintainer email="ole.kettern@curemannheim.de">Ole Kettern</maintainer>
 9
10  <license>TODO</license>
11
12  <buildtool_depend>catkin</buildtool_depend>
13  <build_depend>roscpp</build_depend>
14  <build_depend>rospy</build_depend>
15  <build_depend>message_generation</build_depend>
16  <build_depend>std_msgs</build_depend>
17  <build_depend>geometry_msgs</build_depend>
18  <build_depend>sensor_msgs</build_depend>
19  <build_export_depend>roscpp</build_export_depend>
20  <build_export_depend>rospy</build_export_depend>
21  <exec_depend>roscpp</exec_depend>
22  <exec_depend>rospy</exec_depend>
23  <exec_depend>message_runtime</exec_depend>
24  <exec_depend>std_msgs</exec_depend>
25  <exec_depend>sensor_msgs</exec_depend>
26  <exec_depend>geometry_msgs</exec_depend>
27
28  <export>
29  </export>
30</package>