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),
|
||||
logger{g.log_bitmask},
|
||||
modes(&g.mode1),
|
||||
control_mode(&mode_initializing),
|
||||
G_Dt(0.02f)
|
||||
control_mode(&mode_initializing)
|
||||
{
|
||||
}
|
||||
|
||||
|
@ -152,15 +151,6 @@ void Rover::stats_update(void)
|
|||
#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
|
||||
void Rover::ahrs_update()
|
||||
{
|
||||
|
|
|
@ -126,9 +126,6 @@ public:
|
|||
|
||||
Rover(void);
|
||||
|
||||
// HAL::Callbacks implementation.
|
||||
void loop(void) override;
|
||||
|
||||
private:
|
||||
|
||||
// must be the first AP_Param variable declared to ensure its
|
||||
|
@ -140,9 +137,6 @@ private:
|
|||
Parameters g;
|
||||
ParametersG2 g2;
|
||||
|
||||
// main loop scheduler
|
||||
AP_Scheduler scheduler;
|
||||
|
||||
// mapping between input channels
|
||||
RCMapper rcmap;
|
||||
|
||||
|
@ -237,11 +231,6 @@ private:
|
|||
// true if the compass's initial location has been set
|
||||
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
|
||||
uint32_t flyforward_start_ms;
|
||||
|
||||
|
|
Loading…
Reference in New Issue