mirror of https://github.com/ArduPilot/ardupilot
Rover: let AP_Vehicle handle loop()
This commit is contained in:
parent
51a1ee83a6
commit
ba883e2b89
|
@ -135,8 +135,7 @@ Rover::Rover(void) :
|
||||||
channel_lateral(nullptr),
|
channel_lateral(nullptr),
|
||||||
logger{g.log_bitmask},
|
logger{g.log_bitmask},
|
||||||
modes(&g.mode1),
|
modes(&g.mode1),
|
||||||
control_mode(&mode_initializing),
|
control_mode(&mode_initializing)
|
||||||
G_Dt(0.02f)
|
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -152,15 +151,6 @@ void Rover::stats_update(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
loop() is called rapidly while the sketch is running
|
|
||||||
*/
|
|
||||||
void Rover::loop()
|
|
||||||
{
|
|
||||||
scheduler.loop();
|
|
||||||
G_Dt = scheduler.get_last_loop_time_s();
|
|
||||||
}
|
|
||||||
|
|
||||||
// update AHRS system
|
// update AHRS system
|
||||||
void Rover::ahrs_update()
|
void Rover::ahrs_update()
|
||||||
{
|
{
|
||||||
|
|
|
@ -126,9 +126,6 @@ public:
|
||||||
|
|
||||||
Rover(void);
|
Rover(void);
|
||||||
|
|
||||||
// HAL::Callbacks implementation.
|
|
||||||
void loop(void) override;
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
// must be the first AP_Param variable declared to ensure its
|
// must be the first AP_Param variable declared to ensure its
|
||||||
|
@ -140,9 +137,6 @@ private:
|
||||||
Parameters g;
|
Parameters g;
|
||||||
ParametersG2 g2;
|
ParametersG2 g2;
|
||||||
|
|
||||||
// main loop scheduler
|
|
||||||
AP_Scheduler scheduler;
|
|
||||||
|
|
||||||
// mapping between input channels
|
// mapping between input channels
|
||||||
RCMapper rcmap;
|
RCMapper rcmap;
|
||||||
|
|
||||||
|
@ -237,11 +231,6 @@ private:
|
||||||
// true if the compass's initial location has been set
|
// true if the compass's initial location has been set
|
||||||
bool compass_init_location;
|
bool compass_init_location;
|
||||||
|
|
||||||
// IMU variables
|
|
||||||
// The main loop execution time. Seconds
|
|
||||||
// This is the time between calls to the DCM algorithm and is the Integration time for the gyros.
|
|
||||||
float G_Dt;
|
|
||||||
|
|
||||||
// flyforward timer
|
// flyforward timer
|
||||||
uint32_t flyforward_start_ms;
|
uint32_t flyforward_start_ms;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue