|
|
@ -127,7 +127,6 @@ public: |
|
|
|
Rover(void); |
|
|
|
Rover(void); |
|
|
|
|
|
|
|
|
|
|
|
// HAL::Callbacks implementation.
|
|
|
|
// HAL::Callbacks implementation.
|
|
|
|
void setup(void) override; |
|
|
|
|
|
|
|
void loop(void) override; |
|
|
|
void loop(void) override; |
|
|
|
|
|
|
|
|
|
|
|
private: |
|
|
|
private: |
|
|
@ -384,8 +383,13 @@ private: |
|
|
|
// Steering.cpp
|
|
|
|
// Steering.cpp
|
|
|
|
void set_servos(void); |
|
|
|
void set_servos(void); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// Rover.cpp
|
|
|
|
|
|
|
|
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, |
|
|
|
|
|
|
|
uint8_t &task_count, |
|
|
|
|
|
|
|
uint32_t &log_bit) override; |
|
|
|
|
|
|
|
|
|
|
|
// system.cpp
|
|
|
|
// system.cpp
|
|
|
|
void init_ardupilot(); |
|
|
|
void init_ardupilot() override; |
|
|
|
void startup_ground(void); |
|
|
|
void startup_ground(void); |
|
|
|
void update_ahrs_flyforward(); |
|
|
|
void update_ahrs_flyforward(); |
|
|
|
bool set_mode(Mode &new_mode, ModeReason reason); |
|
|
|
bool set_mode(Mode &new_mode, ModeReason reason); |
|
|
|