mirror of https://github.com/ArduPilot/ardupilot
Rover: remove <startup_ground> message
also remove GROUND_START_DELAY definition
This commit is contained in:
parent
9d030e9424
commit
6738bf9edd
|
@ -36,19 +36,6 @@
|
|||
#error XXX
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// STARTUP BEHAVIOUR
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// GROUND_START_DELAY
|
||||
//
|
||||
#ifndef GROUND_START_DELAY
|
||||
#define GROUND_START_DELAY 0
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// CAMERA control
|
||||
//
|
||||
|
|
|
@ -147,13 +147,6 @@ void Rover::startup_ground(void)
|
|||
{
|
||||
set_mode(mode_initializing, ModeReason::INITIALISED);
|
||||
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "<startup_ground> Ground start");
|
||||
|
||||
#if(GROUND_START_DELAY > 0)
|
||||
gcs().send_text(MAV_SEVERITY_NOTICE, "<startup_ground> With delay");
|
||||
hal.scheduler->delay(GROUND_START_DELAY * 1000);
|
||||
#endif
|
||||
|
||||
// IMU ground start
|
||||
//------------------------
|
||||
//
|
||||
|
|
Loading…
Reference in New Issue