2.3.2. AS CAN Messages Module

2.3.2.1. as_can_msgs

Package for message types used in for CAN to ROS translation in the AS

Maintainers:
Version:

1.2.0

License:

TODO

2.3.2.1.1. Dependencies

Build:
  • roscpp

  • rospy

  • std_msgs

  • message_generation

Build export:
  • roscpp

  • rospy

  • std_msgs

Build tool:

catkin

Execution:
  • roscpp

  • rospy

  • std_msgs

  • message_runtime

2.3.2.1.2. Messages

message as_can_msgs/EbsState
Parameters:
  • header (Header) – Message containing the current state of the emergency brake system. Header containing the time the can message has been received at.

  • state (uint8) – State of the emergency brake system. 0: EBS unavailable, 1: EBS armed, 2: EBS activated.

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

  • engage (bool) – Flag whether the steering control should be engaged.

Message containing a flag whether the steering control should be engaged.

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

  • angle (float64) – Steering wheel angle, request or actual.

Message containg a steering wheel angle.

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

  • count (uint8) – Number of currently observed cones by the perception.

Message containing the number of currently observed cones by the perception.

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

  • mission (uint8) – Chosen Autonomous Mission. 0: ManualDriving, 1: Acceleration, 2: Skidpad, 3: Trackdrive, 4: Braketest / EBS Test, 5: Inspection, 6: Autocross

Message containg the chosen Autonomous Mission on the dashboard display.

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

  • as_status (bool) – Status of the autonomous system part of the shutdown circuit. 0: SDC opened by AS, 1: SDC closed by AS

  • state (uint8) – State of the shutdown unit. 0: Startup, 1: SDC Error, 2: Ready to close, 3: Closed, 4: TSMS Error, 5: HW Error present, 6: HW Error latched

Message containing the state of the shutdown unit and status of the autonomous system part of the shutdown circuit.

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

  • left (float64) – Left wheelspeed.

  • right (float64) – Right wheelspeed.

Message containing left and right wheelspeed for an axis.

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

  • x (float64) – Linear acceleration in x-axis direction.

  • y (float64) – Linear acceleration in y-axis direction.

  • z (float64) – Linear acceleration in z-axis direction.

Message containing the linear acceleration measured by an IMU.

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

  • count (uint32) – Number of currently tracked landmarks by SLAM.

Message containing the number of currently tracked landmarks by SLAM.

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

  • laps (uint8) – Driven laps.

Message containing the driven laps.

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

  • camera (uint8) – State for the sensor. 0: Off, 1: Idle, 2: Up, 3: Error

  • lidar (uint8) – State for the sensor. 0: Off, 1: Idle, 2: Up, 3: Error

  • gps (uint8) – State for the sensor. 0: Off, 1: Idle, 2: Up, 3: Error

  • gps_imu (uint8) – State for the sensor. 0: Off, 1: Idle, 2: Up, 3: Error

  • imu (uint8) – State for the sensor. 0: Off, 1: Idle, 2: Up, 3: Error

  • wheelspeed_front (uint8) – State for the sensor. 0: Off, 1: Idle, 2: Up, 3: Error

  • steering_wheel_angle (uint8) – State for the sensor. 0: Off, 1: Idle, 2: Up, 3: Error

Message containing a state for any sensor.

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

  • state (uint8) – State of the service brake. 1: Service brake disengaged, 2: Service brake engaged, 3: Service Brake available.

Message containing the state of the service brake.

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

  • state (uint8) – State of the checkup sequence.

Message containing the state of the check up sequence running on the asbc.

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

  • as_state (uint8) – Autonomous System state as described in the fs rules 2021. 0: Manual, 1: AS Off, 2: AS Ready, 3: AS Driving, 4: AS Finished, 5: AS Emergency

  • ebs_state (uint8) – Emergency Brake System state as described in the fs rules 2021. 0: unavailable, 1: armed, 2: activated

Message containing the Autonomous System state and Emergency Brake System state, both calculated by the VCU.

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

  • pneumatic_pressure (float64) – Pneumatic pressure of the autonomous brake system

  • SB_pressure (float64) – Pneumatic pressure of the autonomous service brake system

  • tank_pressure (float64) – Pneumatic pressure of the autonomous brake system of the pneumatic tank brake system (measured behind the pressure reducer).

  • override_pressure (float64) – Pneumatic pressure of the autonomous brake system for the brake system behind the manual override valve.

Message containing the pressures in the pneumatic system of the autonomous brake system.

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

  • intact (bool) – Flag containg whether the fuse is still intact.

Message containing the state of an fuse measured by the supply unit.

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

  • use_velocity (bool) – Flag whether velocity should be used to control the inverter (torque as alternative)

Message containing a flag whether the inverter should be controlled via velocity or torque.

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

  • perception (uint8) – State for the module or node. 0: Off, 1: Idle, 2: Up, 3: Error

  • local_mapping (uint8) – State for the module or node. 0: Off, 1: Idle, 2: Up, 3: Error

  • slam (uint8) – State for the module or node. 0: Off, 1: Idle, 2: Up, 3: Error

  • path_planning (uint8) – State for the module or node. 0: Off, 1: Idle, 2: Up, 3: Error

  • motion_planning (uint8) – State for the module or node. 0: Off, 1: Idle, 2: Up, 3: Error

  • control (uint8) – State for the module or node. 0: Off, 1: Idle, 2: Up, 3: Error

Message containing a state for any node or module.

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

  • roll (float64) – Angular rate around the x axis.

  • pitch (float64) – Angular rate around the y axis.

  • yaw (float64) – Angular rate around the z axis.

Message containing the angular rates measured by an IMU.

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

  • torque (float64) – Torque.

Message containing a torque.

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

  • pressure (float64) – Brake pressure.

Message containing a brake pressure.

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

  • emergency_button (bool) – Status of the emergency button of the RES.

  • button (bool) – Status of the button of the RES.

  • switch (bool) – Status of the switch of the RES.

Message containing the button, switch amd emergency button status of the remote emergency system (RES).

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

  • state (uint8) – State of intern mission machine.

Message containing the intern mission machine state.

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

  • finished (bool) – Flag whether the current mission is finished or completed.

Message containing a flag whether the current mission has been finished or completed.

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

  • velocity (float64) – Velocity.

Message containing a velocity.

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

  • asbc_status (uint8) – State of the ASBC derived by the ASIF. 0: OK, 1: No Connection, 2: Error State, 3: Does not toggle

  • acu_status (uint8) – State of the ACU derived by the ASIF. 0: OK, 1: No Connection, 2: Error State, 3: Does not toggle

  • tsa_button (uint8) – State of AS TS activation button, 0: Button not pressed, 1: Short button press, 2: long button press

Message containing the states derived by the ASIF.

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

  • error (bool) – Error flag whether the EBS has an error.

  • asb_error_led (bool) – Flag whether the ASB error LED should light up.

  • toggle (bool) – Flag to implement a periodic toggling to check the correct funtionality of the monitoring module.

Message containing a monitoring error flag, asb error led flag and toggle flag derived and computed by the monitoring module.

2.3.2.1.3. Package definition files

2.3.2.1.3.1. CMakeLists.txt

 1cmake_minimum_required(VERSION 3.0.2)
 2project(as_can_msgs VERSION 1.2.0)
 3
 4## Find catkin macros and libraries
 5find_package(catkin REQUIRED COMPONENTS
 6  roscpp
 7  rospy
 8  std_msgs
 9  message_generation
10)
11
12## Generate messages in the 'msg' folder
13add_message_files(
14  FILES
15  AsifStatus.msg
16  AutonomousMission.msg
17  AutonomousSystemState.msg
18  BrakePressure.msg
19  CheckupSequenceState.msg
20  ConesCountActual.msg
21  ConesCountAll.msg
22  EbsState.msg
23  FuseStatus.msg
24  ImuAcceleration.msg
25  ImuGyro.msg
26  LapCount.msg
27  MissionFinished.msg
28  MissionMachineState.msg
29  MonitoringStatus.msg
30  NodeState.msg
31  PneumaticPressure.msg
32  ResStatus.msg
33  SensorStates.msg
34  ServiceBrakeState.msg
35  ShutdownUnitState.msg
36  SteeringControlEngage.msg
37  SteeringWheelAngle.msg
38  Torque.msg
39  Velocity.msg
40  VelocityTorqueSwitch.msg
41  Wheelspeed.msg	
42)
43
44generate_messages(
45   DEPENDENCIES
46   std_msgs
47 )
48
49catkin_package(
50 CATKIN_DEPENDS message_runtime
51)
52
53include_directories(
54  ${catkin_INCLUDE_DIRS}
55)

2.3.2.1.3.2. package.xml

 1<?xml version="1.0"?>
 2<package format="2">
 3  <name>as_can_msgs</name>
 4  <version>1.2.0</version>
 5  <description>Package for message types used in for CAN to ROS translation in the AS</description>
 6
 7  <maintainer email="ole.kettern@curemannheim.de">Ole Kettern</maintainer>
 8  <maintainer email="martina.scheffler@curemannheim.de">Martina Scheffler</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>std_msgs</build_depend>
16  <build_depend>message_generation</build_depend>
17  <build_export_depend>roscpp</build_export_depend>
18  <build_export_depend>rospy</build_export_depend>
19  <build_export_depend>std_msgs</build_export_depend>
20  <exec_depend>roscpp</exec_depend>
21  <exec_depend>rospy</exec_depend>
22  <exec_depend>std_msgs</exec_depend>
23  <exec_depend>message_runtime</exec_depend>
24  <export>
25  </export>
26</package>