Rover: fold startup_ground back into caller

remove stale comments around same.

rename method to avoid confusion
This commit is contained in:
Peter Barker 2024-04-17 13:07:07 +10:00 committed by Peter Barker
parent c6d5bf5706
commit 67eca06cac
2 changed files with 17 additions and 34 deletions

View File

@ -393,7 +393,7 @@ private:
return control_mode == &mode_auto; return control_mode == &mode_auto;
} }
void startup_INS_ground(void); void startup_INS(void);
void notify_mode(const Mode *new_mode); void notify_mode(const Mode *new_mode);
uint8_t check_digital_pin(uint8_t pin); uint8_t check_digital_pin(uint8_t pin);
bool should_log(uint32_t mask); bool should_log(uint32_t mask);

View File

@ -1,10 +1,3 @@
/*****************************************************************************
The init_ardupilot function processes everything we need for an in - air restart
We will determine later if we are actually on the ground and process a
ground start in that case.
*****************************************************************************/
#include "Rover.h" #include "Rover.h"
static void failsafe_check_static() static void failsafe_check_static()
@ -121,7 +114,21 @@ void Rover::init_ardupilot()
g2.oa.init(); g2.oa.init();
#endif #endif
startup_ground(); set_mode(mode_initializing, ModeReason::INITIALISED);
startup_INS();
#if AP_MISSION_ENABLED
// initialise mission library
mode_auto.mission.init();
#endif
// initialise AP_Logger library
#if HAL_LOGGING_ENABLED
logger.setVehicle_Startup_Writer(
FUNCTOR_BIND(&rover, &Rover::Log_Write_Vehicle_Startup_Messages, void)
);
#endif
Mode *initial_mode = mode_from_mode_num((enum Mode::Number)g.initial_mode.get()); Mode *initial_mode = mode_from_mode_num((enum Mode::Number)g.initial_mode.get());
if (initial_mode == nullptr) { if (initial_mode == nullptr) {
@ -145,30 +152,6 @@ void Rover::init_ardupilot()
initialised = true; initialised = true;
} }
//*********************************************************************************
// This function does all the calibrations, etc. that we need during a ground start
//*********************************************************************************
void Rover::startup_ground(void)
{
set_mode(mode_initializing, ModeReason::INITIALISED);
// IMU ground start
//------------------------
//
startup_INS_ground();
// initialise mission library
mode_auto.mission.init();
// initialise AP_Logger library
#if HAL_LOGGING_ENABLED
logger.setVehicle_Startup_Writer(
FUNCTOR_BIND(&rover, &Rover::Log_Write_Vehicle_Startup_Messages, void)
);
#endif
}
// update the ahrs flyforward setting which can allow // update the ahrs flyforward setting which can allow
// the vehicle's movements to be used to estimate heading // the vehicle's movements to be used to estimate heading
void Rover::update_ahrs_flyforward() void Rover::update_ahrs_flyforward()
@ -285,7 +268,7 @@ bool Rover::set_mode(Mode::Number new_mode, ModeReason reason)
return rover.set_mode(*mode, reason); return rover.set_mode(*mode, reason);
} }
void Rover::startup_INS_ground(void) void Rover::startup_INS(void)
{ {
gcs().send_text(MAV_SEVERITY_INFO, "Beginning INS calibration. Do not move vehicle"); gcs().send_text(MAV_SEVERITY_INFO, "Beginning INS calibration. Do not move vehicle");
hal.scheduler->delay(100); hal.scheduler->delay(100);