mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_HAL_PX4: merge init() and run()
This commit is contained in:
parent
e18884a328
commit
cb61bdd8d1
@ -200,7 +200,7 @@ static void usage(void)
|
||||
}
|
||||
|
||||
|
||||
void HAL_PX4::init(int argc, char * const argv[]) const
|
||||
void HAL_PX4::run(int argc, char * const argv[], Callbacks* callbacks) const
|
||||
{
|
||||
int i;
|
||||
const char *deviceA = UARTA_DEFAULT_DEVICE;
|
||||
@ -215,6 +215,9 @@ void HAL_PX4::init(int argc, char * const argv[]) const
|
||||
exit(1);
|
||||
}
|
||||
|
||||
assert(callbacks);
|
||||
g_callbacks = callbacks;
|
||||
|
||||
for (i=0; i<argc; i++) {
|
||||
if (strcmp(argv[i], "start") == 0) {
|
||||
if (thread_running) {
|
||||
@ -305,13 +308,6 @@ void HAL_PX4::init(int argc, char * const argv[]) const
|
||||
exit(1);
|
||||
}
|
||||
|
||||
void HAL_PX4::run(int argc, char * const argv[], Callbacks* callbacks) const
|
||||
{
|
||||
assert(callbacks);
|
||||
g_callbacks = callbacks;
|
||||
init(argc, argv);
|
||||
}
|
||||
|
||||
const AP_HAL::HAL& AP_HAL::get_HAL() {
|
||||
static const HAL_PX4 hal_px4;
|
||||
return hal_px4;
|
||||
|
@ -14,7 +14,6 @@
|
||||
class HAL_PX4 : public AP_HAL::HAL {
|
||||
public:
|
||||
HAL_PX4();
|
||||
void init(int argc, char * const argv[]) const;
|
||||
void run(int argc, char* const argv[], Callbacks* callbacks) const override;
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user