dbw_mkz_msgs/BrakeInfoReport Message

File: dbw_mkz_msgs/BrakeInfoReport.msg

Raw Message Definition

Header header

# Wheel torques (Nm)
float32 brake_torque_request
float32 brake_torque_actual
float32 wheel_torque_actual

# Vehicle Acceleration (m/s^2)
float32 accel_over_ground

# Brake Pedal
QualityFactor brake_pedal_qf

# Hill Start Assist
HillStartAssist hsa

# Anti-lock Brakes
bool abs_active
bool abs_enabled

# Stability Control
bool stab_active
bool stab_enabled

# Traction Control
bool trac_active
bool trac_enabled

# Parking Brake
ParkingBrake parking_brake

# Misc
bool stationary

Compact Message Definition

std_msgs/Header header
float32 brake_torque_request
float32 brake_torque_actual
float32 wheel_torque_actual
float32 accel_over_ground
dbw_mkz_msgs/QualityFactor brake_pedal_qf
dbw_mkz_msgs/HillStartAssist hsa
bool abs_active
bool abs_enabled
bool stab_active
bool stab_enabled
bool trac_active
bool trac_enabled
dbw_mkz_msgs/ParkingBrake parking_brake
bool stationary