mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_HAL_AVR: merge init() and run()
This commit is contained in:
parent
1649104382
commit
e18884a328
@ -58,10 +58,12 @@ HAL_AVR_APM1::HAL_AVR_APM1() :
|
|||||||
&avrUtil )
|
&avrUtil )
|
||||||
{}
|
{}
|
||||||
|
|
||||||
void HAL_AVR_APM1::init(int argc, char * const argv[]) const {
|
void HAL_AVR_APM1::run(int argc, char* const argv[], Callbacks* callbacks) const
|
||||||
|
{
|
||||||
|
assert(callbacks);
|
||||||
|
|
||||||
scheduler->init((void*)&isrRegistry);
|
scheduler->init((void*)&isrRegistry);
|
||||||
|
|
||||||
/* uartA is the serial port used for the console, so lets make sure
|
/* uartA is the serial port used for the console, so lets make sure
|
||||||
* it is initialized at boot */
|
* it is initialized at boot */
|
||||||
uartA->begin(115200);
|
uartA->begin(115200);
|
||||||
@ -86,13 +88,6 @@ void HAL_AVR_APM1::init(int argc, char * const argv[]) const {
|
|||||||
PORTE |= _BV(0);
|
PORTE |= _BV(0);
|
||||||
PORTD |= _BV(2);
|
PORTD |= _BV(2);
|
||||||
PORTJ |= _BV(0);
|
PORTJ |= _BV(0);
|
||||||
};
|
|
||||||
|
|
||||||
void HAL_AVR_APM1::run(int argc, char* const argv[], Callbacks* callbacks) const
|
|
||||||
{
|
|
||||||
assert(callbacks);
|
|
||||||
|
|
||||||
init(argc, argv);
|
|
||||||
|
|
||||||
callbacks->setup();
|
callbacks->setup();
|
||||||
scheduler->system_initialized();
|
scheduler->system_initialized();
|
||||||
|
@ -20,7 +20,6 @@
|
|||||||
class HAL_AVR_APM1 : public AP_HAL::HAL {
|
class HAL_AVR_APM1 : public AP_HAL::HAL {
|
||||||
public:
|
public:
|
||||||
HAL_AVR_APM1();
|
HAL_AVR_APM1();
|
||||||
void init(int argc, char * const argv[]) const;
|
|
||||||
void run(int argc, char* const argv[], Callbacks* callbacks) const override;
|
void run(int argc, char* const argv[], Callbacks* callbacks) const override;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -57,10 +57,12 @@ HAL_AVR_APM2::HAL_AVR_APM2() :
|
|||||||
&avrUtil )
|
&avrUtil )
|
||||||
{}
|
{}
|
||||||
|
|
||||||
void HAL_AVR_APM2::init(int argc, char * const argv[]) const {
|
void HAL_AVR_APM2::run(int argc, char* const argv[], Callbacks* callbacks) const
|
||||||
|
{
|
||||||
|
assert(callbacks);
|
||||||
|
|
||||||
scheduler->init((void*)&isrRegistry);
|
scheduler->init((void*)&isrRegistry);
|
||||||
|
|
||||||
/* uartA is the serial port used for the console, so lets make sure
|
/* uartA is the serial port used for the console, so lets make sure
|
||||||
* it is initialized at boot */
|
* it is initialized at boot */
|
||||||
uartA->begin(115200, 128, 128);
|
uartA->begin(115200, 128, 128);
|
||||||
@ -85,13 +87,6 @@ void HAL_AVR_APM2::init(int argc, char * const argv[]) const {
|
|||||||
PORTE |= _BV(0);
|
PORTE |= _BV(0);
|
||||||
PORTD |= _BV(2);
|
PORTD |= _BV(2);
|
||||||
PORTH |= _BV(0);
|
PORTH |= _BV(0);
|
||||||
};
|
|
||||||
|
|
||||||
void HAL_AVR_APM2::run(int argc, char* const argv[], Callbacks* callbacks) const
|
|
||||||
{
|
|
||||||
assert(callbacks);
|
|
||||||
|
|
||||||
init(argc, argv);
|
|
||||||
|
|
||||||
callbacks->setup();
|
callbacks->setup();
|
||||||
scheduler->system_initialized();
|
scheduler->system_initialized();
|
||||||
|
@ -20,7 +20,6 @@
|
|||||||
class HAL_AVR_APM2 : public AP_HAL::HAL {
|
class HAL_AVR_APM2 : public AP_HAL::HAL {
|
||||||
public:
|
public:
|
||||||
HAL_AVR_APM2();
|
HAL_AVR_APM2();
|
||||||
void init(int argc, char * const argv[]) const;
|
|
||||||
void run(int argc, char* const argv[], Callbacks* callbacks) const override;
|
void run(int argc, char* const argv[], Callbacks* callbacks) const override;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user