mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Periph: added BUZZER_VOLUME parameter
This commit is contained in:
parent
01fc8dcb3c
commit
5ee66ab6a8
@ -26,6 +26,10 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||||||
// can node baudrate
|
// can node baudrate
|
||||||
GSCALAR(can_baudrate, "CAN_BAUDRATE", 1000000),
|
GSCALAR(can_baudrate, "CAN_BAUDRATE", 1000000),
|
||||||
|
|
||||||
|
#ifdef HAL_PERIPH_ENABLE_BUZZER
|
||||||
|
GSCALAR(buzz_volume, "BUZZER_VOLUME", 100),
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_PERIPH_ENABLE_GPS
|
#ifdef HAL_PERIPH_ENABLE_GPS
|
||||||
// GPS driver
|
// GPS driver
|
||||||
// @Group: GPS_
|
// @Group: GPS_
|
||||||
@ -45,7 +49,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||||||
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
|
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
|
||||||
GOBJECT(baro, "BARO_", AP_Baro),
|
GOBJECT(baro, "BARO_", AP_Baro),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
AP_VAREND
|
AP_VAREND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -17,11 +17,15 @@ public:
|
|||||||
k_param_can_node,
|
k_param_can_node,
|
||||||
k_param_can_baudrate,
|
k_param_can_baudrate,
|
||||||
k_param_baro,
|
k_param_baro,
|
||||||
|
k_param_buzz_volume,
|
||||||
};
|
};
|
||||||
|
|
||||||
AP_Int16 format_version;
|
AP_Int16 format_version;
|
||||||
AP_Int16 can_node;
|
AP_Int16 can_node;
|
||||||
AP_Int32 can_baudrate;
|
AP_Int32 can_baudrate;
|
||||||
|
#ifdef HAL_PERIPH_ENABLE_BUZZER
|
||||||
|
AP_Int8 buzz_volume;
|
||||||
|
#endif
|
||||||
|
|
||||||
Parameters() {}
|
Parameters() {}
|
||||||
};
|
};
|
||||||
|
@ -371,7 +371,8 @@ static void handle_beep_command(CanardInstance* ins, CanardRxTransfer* transfer)
|
|||||||
fix_float16(req.duration);
|
fix_float16(req.duration);
|
||||||
buzzer_start_ms = AP_HAL::millis();
|
buzzer_start_ms = AP_HAL::millis();
|
||||||
buzzer_len_ms = req.duration*1000;
|
buzzer_len_ms = req.duration*1000;
|
||||||
hal.util->toneAlarm_set_buzzer_tone(req.frequency, 1, uint32_t(req.duration*1000));
|
float volume = constrain_float(periph.g.buzz_volume/100.0, 0, 1);
|
||||||
|
hal.util->toneAlarm_set_buzzer_tone(req.frequency, volume, uint32_t(req.duration*1000));
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user