mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter : initialise surface to be tracked
This sets the surface to be tracked in SurfaceTracking with the value of SURFTRAK_MODE parameter. Co-Authored-By: Peter Hall <33176108+IamPete1@users.noreply.github.com>
This commit is contained in:
parent
e1ded4e3f6
commit
477f2824b9
@ -285,9 +285,11 @@ private:
|
|||||||
};
|
};
|
||||||
// set surface to track
|
// set surface to track
|
||||||
void set_surface(Surface new_surface);
|
void set_surface(Surface new_surface);
|
||||||
|
// initialise surface tracking
|
||||||
|
void init(Surface surf) { surface = surf; }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
Surface surface = Surface::GROUND;
|
Surface surface;
|
||||||
uint32_t last_update_ms; // system time of last update to target_alt_cm
|
uint32_t last_update_ms; // system time of last update to target_alt_cm
|
||||||
uint32_t last_glitch_cleared_ms; // system time of last handle glitch recovery
|
uint32_t last_glitch_cleared_ms; // system time of last handle glitch recovery
|
||||||
bool valid_for_logging; // true if target_alt_cm is valid for logging
|
bool valid_for_logging; // true if target_alt_cm is valid for logging
|
||||||
|
@ -76,6 +76,10 @@ void Copter::init_ardupilot()
|
|||||||
|
|
||||||
init_rc_in(); // sets up rc channels from radio
|
init_rc_in(); // sets up rc channels from radio
|
||||||
|
|
||||||
|
// initialise surface to be tracked in SurfaceTracking
|
||||||
|
// must be before rc init to not override inital switch position
|
||||||
|
surface_tracking.init((SurfaceTracking::Surface)copter.g2.surftrak_mode.get());
|
||||||
|
|
||||||
// allocate the motors class
|
// allocate the motors class
|
||||||
allocate_motors();
|
allocate_motors();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user