Rover: system.cpp correct whitespace, remove tabs
This commit is contained in:
parent
c2adb04a93
commit
52aa6b5767
@ -48,7 +48,7 @@ int8_t Rover::reboot_board(uint8_t argc, const Menu::arg *argv)
|
|||||||
void Rover::run_cli(AP_HAL::UARTDriver *port)
|
void Rover::run_cli(AP_HAL::UARTDriver *port)
|
||||||
{
|
{
|
||||||
// disable the failsafe code in the CLI
|
// disable the failsafe code in the CLI
|
||||||
hal.scheduler->register_timer_failsafe(nullptr,1);
|
hal.scheduler->register_timer_failsafe(nullptr, 1);
|
||||||
|
|
||||||
// disable the mavlink delay callback
|
// disable the mavlink delay callback
|
||||||
hal.scheduler->register_delay_callback(nullptr, 5);
|
hal.scheduler->register_delay_callback(nullptr, 5);
|
||||||
@ -62,7 +62,7 @@ void Rover::run_cli(AP_HAL::UARTDriver *port)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // CLI_ENABLED
|
#endif // CLI_ENABLED
|
||||||
|
|
||||||
static void mavlink_delay_cb_static()
|
static void mavlink_delay_cb_static()
|
||||||
{
|
{
|
||||||
@ -105,7 +105,7 @@ void Rover::init_ardupilot()
|
|||||||
// Register mavlink_delay_cb, which will run anytime you have
|
// Register mavlink_delay_cb, which will run anytime you have
|
||||||
// more than 5ms remaining in your call to hal.scheduler->delay
|
// more than 5ms remaining in your call to hal.scheduler->delay
|
||||||
hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);
|
hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);
|
||||||
|
|
||||||
BoardConfig.init();
|
BoardConfig.init();
|
||||||
|
|
||||||
ServoRelayEvents.set_channel_mask(0xFFF0);
|
ServoRelayEvents.set_channel_mask(0xFFF0);
|
||||||
@ -140,13 +140,13 @@ void Rover::init_ardupilot()
|
|||||||
log_init();
|
log_init();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (g.compass_enabled==true) {
|
if (g.compass_enabled == true) {
|
||||||
if (!compass.init()|| !compass.read()) {
|
if (!compass.init()|| !compass.read()) {
|
||||||
cliSerial->println("Compass initialisation failed!");
|
cliSerial->println("Compass initialisation failed!");
|
||||||
g.compass_enabled = false;
|
g.compass_enabled = false;
|
||||||
} else {
|
} else {
|
||||||
ahrs.set_compass(&compass);
|
ahrs.set_compass(&compass);
|
||||||
//compass.get_offsets(); // load offsets to account for airframe magnetic interference
|
// compass.get_offsets(); // load offsets to account for airframe magnetic interference
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -208,21 +208,21 @@ void Rover::init_ardupilot()
|
|||||||
reset_control_switch();
|
reset_control_switch();
|
||||||
}
|
}
|
||||||
|
|
||||||
//********************************************************************************
|
//*********************************************************************************
|
||||||
//This function does all the calibrations, etc. that we need during a ground start
|
// This function does all the calibrations, etc. that we need during a ground start
|
||||||
//********************************************************************************
|
//*********************************************************************************
|
||||||
void Rover::startup_ground(void)
|
void Rover::startup_ground(void)
|
||||||
{
|
{
|
||||||
set_mode(INITIALISING);
|
set_mode(INITIALISING);
|
||||||
|
|
||||||
gcs_send_text(MAV_SEVERITY_INFO,"<startup_ground> Ground start");
|
gcs_send_text(MAV_SEVERITY_INFO, "<startup_ground> Ground start");
|
||||||
|
|
||||||
#if(GROUND_START_DELAY > 0)
|
#if(GROUND_START_DELAY > 0)
|
||||||
gcs_send_text(MAV_SEVERITY_NOTICE,"<startup_ground> With delay");
|
gcs_send_text(MAV_SEVERITY_NOTICE, "<startup_ground> With delay");
|
||||||
delay(GROUND_START_DELAY * 1000);
|
delay(GROUND_START_DELAY * 1000);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//IMU ground start
|
// IMU ground start
|
||||||
//------------------------
|
//------------------------
|
||||||
//
|
//
|
||||||
|
|
||||||
@ -242,7 +242,7 @@ void Rover::startup_ground(void)
|
|||||||
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
|
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
|
||||||
ins.set_dataflash(&DataFlash);
|
ins.set_dataflash(&DataFlash);
|
||||||
|
|
||||||
gcs_send_text(MAV_SEVERITY_INFO,"Ready to drive");
|
gcs_send_text(MAV_SEVERITY_INFO, "Ready to drive");
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -263,7 +263,6 @@ void Rover::set_reverse(bool reverse)
|
|||||||
|
|
||||||
void Rover::set_mode(enum mode mode)
|
void Rover::set_mode(enum mode mode)
|
||||||
{
|
{
|
||||||
|
|
||||||
if (control_mode == mode){
|
if (control_mode == mode){
|
||||||
// don't switch modes if we are already in the correct mode.
|
// don't switch modes if we are already in the correct mode.
|
||||||
return;
|
return;
|
||||||
@ -282,12 +281,12 @@ void Rover::set_mode(enum mode mode)
|
|||||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||||
frsky_telemetry.update_control_mode(control_mode);
|
frsky_telemetry.update_control_mode(control_mode);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (control_mode != AUTO) {
|
if (control_mode != AUTO) {
|
||||||
auto_triggered = false;
|
auto_triggered = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
switch(control_mode) {
|
switch (control_mode) {
|
||||||
case MANUAL:
|
case MANUAL:
|
||||||
case HOLD:
|
case HOLD:
|
||||||
case LEARNING:
|
case LEARNING:
|
||||||
@ -537,7 +536,7 @@ bool Rover::disarm_motors(void)
|
|||||||
mission.reset();
|
mission.reset();
|
||||||
}
|
}
|
||||||
|
|
||||||
//only log if disarming was successful
|
// only log if disarming was successful
|
||||||
change_arm_state();
|
change_arm_state();
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
|
Loading…
Reference in New Issue
Block a user