File: dbw_mkz_msgs/Misc1Report.msg
Raw Message Definition
Header header
# Turn Signal enumeration
TurnSignal turn_signal
# High beams
bool high_beam_headlights
# Front Windshield Wipers enumeration
Wiper wiper
# Ambient Light Sensor enumeration
AmbientLight ambient_light
# Outside air temperature
float32 outside_temperature # Degrees Celsius
# Buttons
bool btn_cc_on # Cruise Control On
bool btn_cc_off # Cruise Control Off
bool btn_cc_on_off # Cruise Control On/Off Toggle
bool btn_cc_res # Cruise Control Resume
bool btn_cc_cncl # Cruise Control Cancel
bool btn_cc_res_cncl # Cruise Control Resume/Cancel
bool btn_cc_res_inc # Cruise Control Resume+
bool btn_cc_res_dec # Cruise Control Resume-
bool btn_cc_set_inc # Cruise Control Set+
bool btn_cc_set_dec # Cruise Control Set-
bool btn_cc_gap_inc # Cruise Control Gap+
bool btn_cc_gap_dec # Cruise Control Gap-
bool btn_la_on_off # Lane Assist On/Off Toggle
bool btn_ld_ok # Left D-Pad OK
bool btn_ld_up # Left D-Pad Up
bool btn_ld_down # Left D-Pad Down
bool btn_ld_left # Left D-Pad Left
bool btn_ld_right # Left D-Pad Right
bool btn_rd_ok # Right D-Pad OK
bool btn_rd_up # Right D-Pad Up
bool btn_rd_down # Right D-Pad Down
bool btn_rd_left # Right D-Pad Left
bool btn_rd_right # Right D-Pad Right
bool btn_vol_inc # Volume increment
bool btn_vol_dec # Volume decrement
bool btn_mute # Volume mute
bool btn_media # Media (source)
bool btn_prev # Media previous
bool btn_next # Media next
bool btn_speak # Speak
bool btn_call_start # Call start/answer
bool btn_call_end # Call end/disconnect
# Faults
bool fault_bus
# Doors
bool door_driver
bool door_passenger
bool door_rear_left
bool door_rear_right
bool door_hood
bool door_trunk
# Passenger seat
bool passenger_detect
bool passenger_airbag
# Seat Belts
bool buckle_driver
bool buckle_passenger
Compact Message Definition
std_msgs/Header header
dbw_mkz_msgs/TurnSignal turn_signal
bool high_beam_headlights
dbw_mkz_msgs/Wiper wiper
dbw_mkz_msgs/AmbientLight ambient_light
float32 outside_temperature
bool btn_cc_on
bool btn_cc_off
bool btn_cc_on_off
bool btn_cc_res
bool btn_cc_cncl
bool btn_cc_res_cncl
bool btn_cc_res_inc
bool btn_cc_res_dec
bool btn_cc_set_inc
bool btn_cc_set_dec
bool btn_cc_gap_inc
bool btn_cc_gap_dec
bool btn_la_on_off
bool btn_ld_ok
bool btn_ld_up
bool btn_ld_down
bool btn_ld_left
bool btn_ld_right
bool btn_rd_ok
bool btn_rd_up
bool btn_rd_down
bool btn_rd_left
bool btn_rd_right
bool btn_vol_inc
bool btn_vol_dec
bool btn_mute
bool btn_media
bool btn_prev
bool btn_next
bool btn_speak
bool btn_call_start
bool btn_call_end
bool fault_bus
bool door_driver
bool door_passenger
bool door_rear_left
bool door_rear_right
bool door_hood
bool door_trunk
bool passenger_detect
bool passenger_airbag
bool buckle_driver
bool buckle_passenger