Rover: removed old LITE mode
this will be replaced with a AHRS_Lite backend later
This commit is contained in:
parent
efd2da3eb8
commit
44a279811d
@ -621,12 +621,10 @@ void loop()
|
||||
|
||||
if (millis() - perf_mon_timer > 20000) {
|
||||
if (mainLoop_count != 0) {
|
||||
#if LITE == DISABLED
|
||||
if (g.log_bitmask & MASK_LOG_PM)
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
Log_Write_Performance();
|
||||
#endif
|
||||
#endif
|
||||
resetPerfData();
|
||||
}
|
||||
}
|
||||
@ -665,9 +663,8 @@ static void fast_loop()
|
||||
gcs_update();
|
||||
#endif
|
||||
|
||||
#if LITE == DISABLED
|
||||
ahrs.update();
|
||||
#endif
|
||||
|
||||
// Read Sonar
|
||||
// ----------
|
||||
if(g.sonar_enabled){
|
||||
@ -683,7 +680,6 @@ static void fast_loop()
|
||||
// uses the yaw from the DCM to give more accurate turns
|
||||
calc_bearing_error();
|
||||
|
||||
#if LITE == DISABLED
|
||||
# if HIL_MODE == HIL_MODE_DISABLED
|
||||
if (g.log_bitmask & MASK_LOG_ATTITUDE_FAST)
|
||||
Log_Write_Attitude((int)ahrs.roll_sensor, (int)ahrs.pitch_sensor, (uint16_t)ahrs.yaw_sensor);
|
||||
@ -691,7 +687,7 @@ static void fast_loop()
|
||||
if (g.log_bitmask & MASK_LOG_IMU)
|
||||
Log_Write_IMU();
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// inertial navigation
|
||||
// ------------------
|
||||
#if INERTIAL_NAVIGATION == ENABLED
|
||||
@ -735,7 +731,6 @@ static void medium_loop()
|
||||
medium_loopCounter++;
|
||||
update_GPS();
|
||||
|
||||
//#if LITE == DISABLED
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
if (g.compass_enabled && compass.read()) {
|
||||
ahrs.set_compass(&compass);
|
||||
@ -745,17 +740,6 @@ static void medium_loop()
|
||||
ahrs.set_compass(NULL);
|
||||
}
|
||||
#endif
|
||||
//#endif
|
||||
/*{
|
||||
cliSerial->print(ahrs.roll_sensor, DEC); cliSerial->printf_P(PSTR("\t"));
|
||||
cliSerial->print(ahrs.pitch_sensor, DEC); cliSerial->printf_P(PSTR("\t"));
|
||||
cliSerial->print(ahrs.yaw_sensor, DEC); cliSerial->printf_P(PSTR("\t"));
|
||||
Vector3f tempaccel = ins.get_accel();
|
||||
cliSerial->print(tempaccel.x, DEC); cliSerial->printf_P(PSTR("\t"));
|
||||
cliSerial->print(tempaccel.y, DEC); cliSerial->printf_P(PSTR("\t"));
|
||||
cliSerial->println(tempaccel.z, DEC);
|
||||
}*/
|
||||
|
||||
break;
|
||||
|
||||
// This case performs some navigation computations
|
||||
@ -779,7 +763,6 @@ cliSerial->println(tempaccel.z, DEC);
|
||||
//-------------------------------------------------
|
||||
case 3:
|
||||
medium_loopCounter++;
|
||||
#if LITE == DISABLED
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
if ((g.log_bitmask & MASK_LOG_ATTITUDE_MED) && !(g.log_bitmask & MASK_LOG_ATTITUDE_FAST))
|
||||
Log_Write_Attitude((int)ahrs.roll_sensor, (int)ahrs.pitch_sensor, (uint16_t)ahrs.yaw_sensor);
|
||||
@ -793,7 +776,6 @@ cliSerial->println(tempaccel.z, DEC);
|
||||
|
||||
if (g.log_bitmask & MASK_LOG_GPS)
|
||||
Log_Write_GPS(g_gps->time, current_loc.lat, current_loc.lng, g_gps->altitude, current_loc.alt, g_gps->ground_speed, g_gps->ground_course, g_gps->fix, g_gps->num_sats);
|
||||
#endif
|
||||
break;
|
||||
|
||||
// This case controls the slow loop
|
||||
@ -824,13 +806,11 @@ static void slow_loop()
|
||||
check_long_failsafe();
|
||||
superslow_loopCounter++;
|
||||
if(superslow_loopCounter >=200) { // 200 = Execute every minute
|
||||
#if LITE == DISABLED
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
if(g.compass_enabled) {
|
||||
compass.save_offsets();
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
superslow_loopCounter = 0;
|
||||
}
|
||||
break;
|
||||
@ -866,10 +846,8 @@ static void slow_loop()
|
||||
|
||||
static void one_second_loop()
|
||||
{
|
||||
#if LITE == DISABLED
|
||||
if (g.log_bitmask & MASK_LOG_CURRENT)
|
||||
Log_Write_Current();
|
||||
#endif
|
||||
// send a heartbeat
|
||||
gcs_send_message(MSG_HEARTBEAT);
|
||||
}
|
||||
|
@ -994,9 +994,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
if (packet.param1 == 1 ||
|
||||
packet.param2 == 1 ||
|
||||
packet.param3 == 1) {
|
||||
#if LITE == DISABLED
|
||||
startup_INS_ground(true);
|
||||
#endif
|
||||
}
|
||||
if (packet.param4 == 1) {
|
||||
trim_radio();
|
||||
|
@ -1,6 +1,5 @@
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#if LITE == DISABLED
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
|
||||
// Code to Write and Read packets from DataFlash log memory
|
||||
@ -672,4 +671,4 @@ static void Log_Write_IMU() {}
|
||||
|
||||
|
||||
#endif // LOGGING_ENABLED
|
||||
#endif
|
||||
|
||||
|
@ -45,7 +45,7 @@ static void calc_nav_steer()
|
||||
nav_steer = g.pidNavSteer.get_pid(bearing_error_cd, nav_gain_scaler);
|
||||
|
||||
if (obstacle) { // obstacle avoidance
|
||||
nav_steer += 9000; // if obstacle in front turn 90° right
|
||||
nav_steer += g.sonar_turn_angle;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -10,14 +10,12 @@ static void init_sonar(void)
|
||||
*/
|
||||
}
|
||||
|
||||
#if LITE == DISABLED
|
||||
// Sensors are not available in HIL_MODE_ATTITUDE
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
|
||||
void ReadSCP1000(void) {}
|
||||
|
||||
#endif // HIL_MODE != HIL_MODE_ATTITUDE
|
||||
#endif
|
||||
|
||||
static void read_battery(void)
|
||||
{
|
||||
|
@ -9,9 +9,7 @@ The init_ardupilot function processes everything we need for an in - air restart
|
||||
#if CLI_ENABLED == ENABLED
|
||||
|
||||
// Functions called from the top-level menu
|
||||
#if LITE == DISABLED
|
||||
static int8_t process_logs(uint8_t argc, const Menu::arg *argv); // in Log.pde
|
||||
#endif
|
||||
static int8_t setup_mode(uint8_t argc, const Menu::arg *argv); // in setup.pde
|
||||
static int8_t test_mode(uint8_t argc, const Menu::arg *argv); // in test.cpp
|
||||
static int8_t reboot_board(uint8_t argc, const Menu::arg *argv);
|
||||
@ -35,9 +33,7 @@ static int8_t main_menu_help(uint8_t argc, const Menu::arg *argv)
|
||||
static const struct Menu::command main_menu_commands[] PROGMEM = {
|
||||
// command function called
|
||||
// ======= ===============
|
||||
#if LITE == DISABLED
|
||||
{"logs", process_logs},
|
||||
#endif
|
||||
{"setup", setup_mode},
|
||||
{"test", test_mode},
|
||||
{"reboot", reboot_board},
|
||||
@ -154,7 +150,6 @@ static void init_ardupilot()
|
||||
|
||||
mavlink_system.sysid = g.sysid_this_mav;
|
||||
|
||||
#if LITE == DISABLED
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
DataFlash.Init(); // DataFlash log initialization
|
||||
if (!DataFlash.CardInserted()) {
|
||||
@ -168,7 +163,6 @@ static void init_ardupilot()
|
||||
DataFlash.start_new_log();
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
|
||||
@ -176,7 +170,6 @@ static void init_ardupilot()
|
||||
adc.Init(); // APM ADC library initialization
|
||||
#endif
|
||||
|
||||
#if LITE == DISABLED
|
||||
if (g.compass_enabled==true) {
|
||||
compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft
|
||||
if (!compass.init()|| !compass.read()) {
|
||||
@ -187,39 +180,6 @@ static void init_ardupilot()
|
||||
//compass.get_offsets(); // load offsets to account for airframe magnetic interference
|
||||
}
|
||||
}
|
||||
#else
|
||||
I2c.begin();
|
||||
I2c.timeOut(20);
|
||||
|
||||
// I2c.setSpeed(true);
|
||||
|
||||
if (!compass.init()) {
|
||||
cliSerial->println("compass initialisation failed!");
|
||||
while (1) ;
|
||||
}
|
||||
|
||||
compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft.
|
||||
compass.set_offsets(0,0,0); // set offsets to account for surrounding interference
|
||||
|
||||
cliSerial->print("Compass auto-detected as: ");
|
||||
switch( compass.product_id ) {
|
||||
case AP_COMPASS_TYPE_HIL:
|
||||
cliSerial->println("HIL");
|
||||
break;
|
||||
case AP_COMPASS_TYPE_HMC5843:
|
||||
cliSerial->println("HMC5843");
|
||||
break;
|
||||
case AP_COMPASS_TYPE_HMC5883L:
|
||||
cliSerial->println("HMC5883L");
|
||||
break;
|
||||
default:
|
||||
cliSerial->println("unknown");
|
||||
break;
|
||||
}
|
||||
|
||||
delay(3000);
|
||||
|
||||
#endif
|
||||
// initialise sonar
|
||||
init_sonar();
|
||||
#endif
|
||||
@ -284,10 +244,8 @@ static void init_ardupilot()
|
||||
|
||||
startup_ground();
|
||||
|
||||
#if LITE == DISABLED
|
||||
if (g.log_bitmask & MASK_LOG_CMD)
|
||||
Log_Write_Startup(TYPE_GROUNDSTART_MSG);
|
||||
#endif
|
||||
|
||||
set_mode(MANUAL);
|
||||
|
||||
@ -315,13 +273,11 @@ static void startup_ground(void)
|
||||
// -----------------------
|
||||
demo_servos(1);
|
||||
|
||||
#if LITE == DISABLED
|
||||
//IMU ground start
|
||||
//------------------------
|
||||
//
|
||||
|
||||
startup_INS_ground(false);
|
||||
#endif
|
||||
|
||||
// read the radio to set trims
|
||||
// ---------------------------
|
||||
@ -369,11 +325,8 @@ static void set_mode(enum mode mode)
|
||||
break;
|
||||
}
|
||||
|
||||
#if LITE == DISABLED
|
||||
if (g.log_bitmask & MASK_LOG_MODE)
|
||||
Log_Write_Mode(control_mode);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
static void check_long_failsafe()
|
||||
@ -398,7 +351,6 @@ static void check_long_failsafe()
|
||||
}
|
||||
}
|
||||
|
||||
#if LITE == DISABLED
|
||||
static void startup_INS_ground(bool force_accel_level)
|
||||
{
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
@ -431,7 +383,6 @@ static void startup_INS_ground(bool force_accel_level)
|
||||
digitalWrite(A_LED_PIN, LED_OFF);
|
||||
digitalWrite(C_LED_PIN, LED_OFF);
|
||||
}
|
||||
#endif
|
||||
|
||||
static void update_GPS_light(void)
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user