#include "Tracker.h" /* update INS and attitude */ void Tracker::update_ahrs() { ahrs.update(); } /* read and update compass */ void Tracker::update_compass(void) { if (g.compass_enabled && compass.read()) { ahrs.set_compass(&compass); if (should_log(MASK_LOG_COMPASS)) { logger.Write_Compass(); } } } /* calibrate compass */ void Tracker::compass_cal_update() { if (!hal.util->get_soft_armed()) { compass.compass_cal_update(); } } /* Accel calibration */ void Tracker::accel_cal_update() { if (hal.util->get_soft_armed()) { return; } ins.acal_update(); float trim_roll, trim_pitch; if (ins.get_new_trim(trim_roll, trim_pitch)) { ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0)); } } /* read the GPS */ void Tracker::update_GPS(void) { gps.update(); static uint32_t last_gps_msg_ms; static uint8_t ground_start_count = 5; if (gps.last_message_time_ms() != last_gps_msg_ms && gps.status() >= AP_GPS::GPS_OK_FIX_3D) { last_gps_msg_ms = gps.last_message_time_ms(); if (ground_start_count > 1) { ground_start_count--; } else if (ground_start_count == 1) { // We countdown N number of good GPS fixes // so that the altitude is more accurate // ------------------------------------- if (current_loc.lat == 0 && current_loc.lng == 0) { ground_start_count = 5; } else { // Now have an initial GPS position // use it as the HOME position in future startups current_loc = gps.location(); set_home(current_loc); if (g.compass_enabled) { // Set compass declination automatically compass.set_initial_location(gps.location().lat, gps.location().lng); } ground_start_count = 0; } } } } void Tracker::handle_battery_failsafe(const char* type_str, const int8_t action) { // NOP // useful failsafes in the future would include actually recalling the vehicle // that is tracked before the tracker loses power to continue tracking it } // update sensors and subsystems present, enabled and healthy flags for reporting to GCS void Tracker::update_sensor_status_flags() { // default sensors present control_sensors_present = MAVLINK_SENSOR_PRESENT_DEFAULT; // first what sensors/controllers we have if (g.compass_enabled) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG; // compass present } if (gps.status() > AP_GPS::NO_GPS) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS; } if (logger.logging_present()) { // primary logging only (usually File) control_sensors_present |= MAV_SYS_STATUS_LOGGING; } // all present sensors enabled by default except rate control, attitude stabilization, yaw, altitude, position control and motor output which we will set individually control_sensors_enabled = control_sensors_present & (~MAV_SYS_STATUS_LOGGING & ~MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS & ~MAV_SYS_STATUS_SENSOR_BATTERY); if (logger.logging_enabled()) { control_sensors_enabled |= MAV_SYS_STATUS_LOGGING; } // set motors outputs as enabled if safety switch is not disarmed (i.e. either NONE or ARMED) if (hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED) { control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS; } if (battery.num_instances() > 0) { control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_BATTERY; } // default to all healthy except compass and gps which we set individually control_sensors_health = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_3D_MAG & ~MAV_SYS_STATUS_SENSOR_GPS); if (g.compass_enabled && compass.healthy(0) && ahrs.use_compass()) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG; } if (gps.is_healthy()) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS; } if (!ins.get_gyro_health_all() || !ins.gyro_calibrated_ok_all()) { control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_GYRO; } if (!ins.get_accel_health_all()) { control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_ACCEL; } if (ahrs.initialised() && !ahrs.healthy()) { // AHRS subsystem is unhealthy control_sensors_health &= ~MAV_SYS_STATUS_AHRS; } if (logger.logging_failed()) { control_sensors_health &= ~MAV_SYS_STATUS_LOGGING; } if (!battery.healthy() || battery.has_failsafed()) { control_sensors_enabled &= ~MAV_SYS_STATUS_SENSOR_BATTERY; } if (ins.calibrating()) { // while initialising the gyros and accels are not enabled control_sensors_enabled &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL); control_sensors_health &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL); } }