mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
HAL_VRBrain: match plane 3.9.0
This commit is contained in:
parent
b378446472
commit
388cbf5cbd
@ -84,12 +84,6 @@ void VRBRAINGPIO::pinMode(uint8_t pin, uint8_t output)
|
||||
}
|
||||
}
|
||||
|
||||
int8_t VRBRAINGPIO::analogPinToDigitalPin(uint8_t pin)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
||||
uint8_t VRBRAINGPIO::read(uint8_t pin) {
|
||||
switch (pin) {
|
||||
|
||||
|
@ -23,7 +23,6 @@ public:
|
||||
VRBRAINGPIO();
|
||||
void init() override;
|
||||
void pinMode(uint8_t pin, uint8_t output) override;
|
||||
int8_t analogPinToDigitalPin(uint8_t pin) override;
|
||||
uint8_t read(uint8_t pin) override;
|
||||
void write(uint8_t pin, uint8_t value) override;
|
||||
void toggle(uint8_t pin) override;
|
||||
|
@ -173,17 +173,13 @@ void VRBRAINScheduler::delay_microseconds_boost(uint16_t usec)
|
||||
|
||||
void VRBRAINScheduler::delay(uint16_t ms)
|
||||
{
|
||||
if (!in_main_thread()) {
|
||||
::printf("ERROR: delay() from timer process\n");
|
||||
return;
|
||||
}
|
||||
perf_begin(_perf_delay);
|
||||
uint64_t start = AP_HAL::micros64();
|
||||
|
||||
while ((AP_HAL::micros64() - start)/1000 < ms &&
|
||||
!_vrbrain_thread_should_exit) {
|
||||
delay_microseconds_semaphore(1000);
|
||||
if (_min_delay_cb_ms <= ms) {
|
||||
if (in_main_thread() && _min_delay_cb_ms <= ms) {
|
||||
call_delay_cb();
|
||||
}
|
||||
}
|
||||
|
@ -127,7 +127,8 @@ bool VRBRAINUtil::get_system_id(char buf[40])
|
||||
board_type,
|
||||
(unsigned)serialid[0], (unsigned)serialid[1], (unsigned)serialid[2], (unsigned)serialid[3],
|
||||
(unsigned)serialid[4], (unsigned)serialid[5], (unsigned)serialid[6], (unsigned)serialid[7],
|
||||
(unsigned)serialid[8], (unsigned)serialid[9], (unsigned)serialid[10],(unsigned)serialid[11]);
|
||||
(unsigned)serialid[8], (unsigned)serialid[9], (unsigned)serialid[10],(unsigned)serialid[11]);
|
||||
buf[39] = 0;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user