MonitorReport
This is a ROS message definition.
Source
std_msgs/Header header
# Status
bool fault # Any fault
bool shutoff # Shutoff due to fault action
bool shutoff_on_motion # Shutoff deferred due to lack of vehicle motion
bool stationary # Vehicle is stationary
# Fault enumerations
uint8 FAULT_UNKNOWN=0
uint8 FAULT_NONE=1
uint8 FAULT_FAULT=2
# Test fault to verify shutoff action
uint8 fault_test
# Aggregate of several faults
uint8 fault_system # Any fault related to system enable/disable
uint8 fault_steer # Any fault related to steer control
uint8 fault_brake # Any fault related to brake control
uint8 fault_thrtl # Any fault related to throttle control
uint8 fault_gear # Any fault related to gear control
uint8 fault_ulc # Any fault related to the ULC
# Vehicle velocity measurement mismatch with OEM
uint8 fault_vehicle_velocity
# Steer faults
uint8 fault_steer_feedback # Steering wheel angle measurement mismatch with OEM
uint8 fault_steer_input # Steering column torque measurement mismatch with OEM
uint8 fault_steer_param # Steering parameter mismatch with DBW
uint8 fault_steer_limit # Steering limit calculation mismatch with DBW
uint8 fault_steer_override # Steering override calculation mismatch with DBW
uint8 fault_steer_cmd # Steering actuator command mismatch with OEM and DBW
uint8 fault_steer_cmd_rate # Steering actuator command rate faster than DBW and limit
uint8 fault_steer_cmd_en # Steering actuator command without matching command enable
uint8 fault_steer_cmd_sys # Steering actuator command with system disabled
uint8 fault_steer_cmd_ovr # Steering actuator command with override
# Brake faults
uint8 fault_brake_feedback # Brake actuator output torque/pressure measurement mismatch with OEM
uint8 fault_brake_input # Brake pedal input torque/pressure measurement mismatch with OEM
uint8 fault_brake_param # Brake parameter mismatch with DBW
uint8 fault_brake_limit # Brake limit calculation mismatch with DBW
uint8 fault_brake_override # Brake override calculation mismatch with DBW
uint8 fault_brake_cmd # Brake actuator command mismatch with OEM and DBW
uint8 fault_brake_cmd_ulc # Brake command generated by ULC command without matching ULC command
uint8 fault_brake_cmd_en # Brake actuator command without matching command enable
uint8 fault_brake_cmd_sys # Brake actuator command with system disabled
uint8 fault_brake_cmd_ovr # Brake actuator command with override
# Throttle faults
uint8 fault_thrtl_feedback # Accelerator pedal output measurement mismatch with OEM
uint8 fault_thrtl_input # Accelerator pedal input measurement mismatch with OEM
uint8 fault_thrtl_param # Throttle parameter mismatch with DBW
uint8 fault_thrtl_limit # Throttle limit calculation mismatch with DBW
uint8 fault_thrtl_override # Throttle override calculation mismatch with DBW
uint8 fault_thrtl_cmd # Throttle actuator command mismatch with OEM and DBW
uint8 fault_thrtl_cmd_ulc # Throttle command generated by ULC command without matching ULC command
uint8 fault_thrtl_cmd_en # Throttle actuator command without matching command enable
uint8 fault_thrtl_cmd_sys # Throttle actuator command with system disabled
uint8 fault_thrtl_cmd_ovr # Throttle actuator command with override
# Gear faults
uint8 fault_gear_feedback # Transmission gear measurement mismatch with OEM
uint8 fault_gear_input # Gear input selection measurement mismatch with OEM
uint8 fault_gear_param # Gear parameter mismatch with DBW
uint8 fault_gear_override # Gear override calculation mismatch with DBW
uint8 fault_gear_cmd # Gear actuator command mismatch with OEM and DBW
uint8 fault_gear_cmd_ulc # Gear command generated by ULC command without matching ULC command
# System faults
uint8 fault_system_param # System parameter mismatch with DBW
# Debug
bool steer_cmd_match_oem
bool steer_cmd_match_dbw
bool brake_cmd_match_oem
bool brake_cmd_match_dbw
bool thrtl_cmd_match_oem
bool thrtl_cmd_match_dbw
bool gear_cmd_match_oem
bool gear_cmd_match_dbw