mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 23:43:58 -04:00
AP_HAL_ChibiOS: make ToneAlarm compilation conditional on presence of
alarm pin
This commit is contained in:
parent
9ab5ea87e0
commit
59b2d44323
@ -56,7 +56,7 @@ void Scheduler::init()
|
||||
_timer_thread, /* Thread function. */
|
||||
this); /* Thread parameter. */
|
||||
|
||||
// setup the timer thread - this will call tasks at 1kHz
|
||||
// setup the uavcan thread - this will call tasks at 1kHz
|
||||
#if HAL_WITH_UAVCAN
|
||||
_uavcan_thread_ctx = chThdCreateStatic(_uavcan_thread_wa,
|
||||
sizeof(_uavcan_thread_wa),
|
||||
@ -72,12 +72,13 @@ void Scheduler::init()
|
||||
this); /* Thread parameter. */
|
||||
|
||||
// the toneAlarm thread runs at a medium priority
|
||||
#ifdef HAL_PWM_ALARM
|
||||
_toneAlarm_thread_ctx = chThdCreateStatic(_toneAlarm_thread_wa,
|
||||
sizeof(_toneAlarm_thread_wa),
|
||||
APM_TONEALARM_PRIORITY, /* Initial priority. */
|
||||
_toneAlarm_thread, /* Thread function. */
|
||||
this); /* Thread parameter. */
|
||||
|
||||
#endif
|
||||
// the IO thread runs at lower priority
|
||||
_io_thread_ctx = chThdCreateStatic(_io_thread_wa,
|
||||
sizeof(_io_thread_wa),
|
||||
@ -309,6 +310,7 @@ void Scheduler::_rcin_thread(void *arg)
|
||||
((RCInput *)hal.rcin)->_timer_tick();
|
||||
}
|
||||
}
|
||||
#ifdef HAL_PWM_ALARM
|
||||
|
||||
void Scheduler::_toneAlarm_thread(void *arg)
|
||||
{
|
||||
@ -324,7 +326,7 @@ void Scheduler::_toneAlarm_thread(void *arg)
|
||||
Util::from(hal.util)->_toneAlarm_timer_tick();
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
void Scheduler::_run_io(void)
|
||||
{
|
||||
if (_in_io_proc) {
|
||||
|
@ -1,7 +1,10 @@
|
||||
#include "ToneAlarm.h"
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
|
||||
#ifdef HAL_PWM_ALARM
|
||||
|
||||
#include "ToneAlarm.h"
|
||||
|
||||
using namespace ChibiOS;
|
||||
|
||||
struct ToneAlarm::pwmGroup ToneAlarm::pwm_group = HAL_PWM_ALARM;
|
||||
@ -261,3 +264,4 @@ bool ToneAlarm::init_tune()
|
||||
|
||||
return true;
|
||||
}
|
||||
#endif
|
@ -32,9 +32,6 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace ChibiOS;
|
||||
|
||||
static int state;
|
||||
ToneAlarm Util::_toneAlarm;
|
||||
|
||||
extern "C" {
|
||||
size_t mem_available(void);
|
||||
void *malloc_ccm(size_t size);
|
||||
@ -143,6 +140,10 @@ void Util::set_imu_target_temp(int8_t *target)
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef HAL_PWM_ALARM
|
||||
static int state;
|
||||
ToneAlarm Util::_toneAlarm;
|
||||
|
||||
bool Util::toneAlarm_init()
|
||||
{
|
||||
return _toneAlarm.init();
|
||||
@ -175,5 +176,5 @@ void Util::_toneAlarm_timer_tick() {
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
#endif // HAL_PWM_ALARM
|
||||
#endif //CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
|
@ -46,14 +46,19 @@ public:
|
||||
// IMU temperature control
|
||||
void set_imu_temp(float current);
|
||||
void set_imu_target_temp(int8_t *target);
|
||||
|
||||
#ifdef HAL_PWM_ALARM
|
||||
bool toneAlarm_init();
|
||||
void toneAlarm_set_tune(uint8_t tone);
|
||||
void _toneAlarm_timer_tick();
|
||||
|
||||
static ToneAlarm& get_ToneAlarm() { return _toneAlarm; }
|
||||
#endif
|
||||
|
||||
private:
|
||||
#ifdef HAL_PWM_ALARM
|
||||
static ToneAlarm _toneAlarm;
|
||||
#endif
|
||||
void* try_alloc_from_ccm_ram(size_t size);
|
||||
uint32_t available_memory_in_ccm_ram(void);
|
||||
|
||||
|
@ -568,7 +568,8 @@ def write_PWM_config(f):
|
||||
if not is_int(chan_str) or not is_int(timer_str):
|
||||
error("Bad timer channel %s" % alarm.label)
|
||||
n = int(timer_str)
|
||||
f.write('\n// Alarm PWM output config\n')
|
||||
f.write('\n')
|
||||
f.write('// Alarm PWM output config\n')
|
||||
f.write('#define STM32_PWM_USE_TIM%u TRUE\n' % n)
|
||||
f.write('#define STM32_TIM%u_SUPPRESS_ISR\n' % n)
|
||||
|
||||
@ -603,7 +604,11 @@ def write_PWM_config(f):
|
||||
}\n''' %
|
||||
(chan-1, pwm_clock, period, chan_mode[0],
|
||||
chan_mode[1], chan_mode[2], chan_mode[3], n))
|
||||
else:
|
||||
f.write('\n')
|
||||
f.write('// No Alarm output pin defined\n')
|
||||
f.write('#undef HAL_PWM_ALARM\n')
|
||||
f.write('\n')
|
||||
|
||||
f.write('// PWM timer config\n')
|
||||
for t in sorted(pwm_timers):
|
||||
|
Loading…
Reference in New Issue
Block a user