Skip to content

Commit

Permalink
Merge branch 'feat/add-mrm-v0.6-launch-based-on-based-on-v3.0.0' into…
Browse files Browse the repository at this point in the history
… feat/add-msg-mrm-state
  • Loading branch information
TetsuKawa authored Jun 27, 2024
2 parents 2b49884 + 003f8bd commit 6c42491
Show file tree
Hide file tree
Showing 3 changed files with 56 additions and 0 deletions.
2 changes: 2 additions & 0 deletions tier4_system_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@ rosidl_generate_interfaces(${PROJECT_NAME}
"msg/DiagnosticLink.msg"
"msg/DiagnosticNode.msg"
"msg/OperationModeAvailability.msg"
"msg/ElectionStatus.msg"
"msg/ElectionCommunication.msg"
"msg/EmergencyGoalsClearCommand.msg"
"msg/EmergencyGoalsStamped.msg"
"msg/EmergencyState.msg"
Expand Down
28 changes: 28 additions & 0 deletions tier4_system_msgs/msg/ElectionCommunication.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
# node_id
uint8 MAIN_ECU = 0
uint8 SUB_ECU = 1
uint8 MAIN_VCU = 2
uint8 SUB_VCU = 3

# type
uint8 HEARTBEAT_MSG = 0
uint8 ELECTION_MSG = 1
uint8 REPLY_MSG = 2
uint8 LEADER_MSG = 3

# link
# The link is a 4-bit data.
# In the case of a leader message, it represents the selected path,
# and in the case of an election message or a replay message, it represents the connected status.
# The bits represent the state of the Main ECU, Sub ECU, Main VCU, and Sub VCU in order from the leading bit.
# For example:
# If this message is a reply message with link=0x1010,
# the node that sent this message is connected only to the Main ECU and Main VCU.

builtin_interfaces/Time stamp
uint8 node_id # msg sender
uint8 type # msg type
uint8 term # term of election msg
uint8 link # For leader msg, the selected path; for election or reply msg, the connection status
uint8 heartbeat # heartbeat from 0 to 15
uint8 checksum # checksum for CAN data
26 changes: 26 additions & 0 deletions tier4_system_msgs/msg/ElectionStatus.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
# leader_id
uint8 MAIN_ECU = 0
uint8 SUB_ECU = 1
uint8 MAIN_VCU = 2
uint8 SUB_VCU = 3

# path_info
# The path_info is a 4-bit data which represents the selected path,
# The bits represent the state of the Main ECU, Sub ECU, Main VCU, and Sub VCU in order from the leading bit.
# For example:
# If path_info=0x1010,
# the path selects the Main ECU and Main VCU.

builtin_interfaces/Time stamp
uint8 leader_id # leader of all nodes
uint8 path_info # The path used for driving
tier4_system_msgs/MrmState mrm_state # The mrm behavior determined for the entire system and its state
uint8 election_start_count # means the number of times a failure has occurred.
bool in_election # whether an election is in progress
bool has_received_availability # If false, it means that the Availability UDP packet from Autoware has not been received or has timed out.
bool has_received_mrm_state # If false, it means that the MrmState UDP packet from Autoware has not been received or has timed out.
bool is_autoware_emergency # whether Autoware is in a normal state
bool is_main_ecu_connected # whether this node is able to communicate properly with the Main ECU
bool is_sub_ecu_connected # whether this node is able to communicate properly with the Sub ECU
bool is_main_vcu_connected # whether this node is able to communicate properly with the Main VCU
bool is_sub_vcu_connected # whether this node is able to communicate properly with the Sub VCU

0 comments on commit 6c42491

Please sign in to comment.