void Plane::geofence_send_status(mavlink_channel_t chan) { if (geofence_enabled() && geofence_state != nullptr) { mavlink_msg_fence_status_send(chan, (int8_t)geofence_state->fence_triggered, geofence_state->breach_count, geofence_state->breach_type, geofence_state->breach_time); } }
/* * return true if geofencing allows stick mixing. When we have * triggered failsafe and are in GUIDED mode then stick mixing is * disabled. Otherwise the aircraft may not be able to recover from * a breach of the geo-fence */ bool Plane::geofence_stickmixing(void) { if (geofence_enabled() && geofence_state != nullptr && geofence_state->fence_triggered && (control_mode == GUIDED || control_mode == AVOID_ADSB)) { // don't mix in user input return false; } // normal mixing rules return true; }
/* * return true if geofencing allows stick mixing. When we have * triggered failsafe and are in GUIDED mode then stick mixing is * disabled. Otherwise the aircraft may not be able to recover from * a breach of the geo-fence */ bool Plane::geofence_stickmixing(void) { if (geofence_enabled() && geofence_state != NULL && geofence_state->fence_triggered && control_mode == GUIDED) { // don't mix in user input return false; } // normal mixing rules return true; }
/* * check if we have breached the geo-fence */ void Plane::geofence_check(bool altitude_check_only) { if (!geofence_enabled()) { // switch back to the chosen control mode if still in // GUIDED to the return point if (geofence_state != nullptr && (g.fence_action == FENCE_ACTION_GUIDED || g.fence_action == FENCE_ACTION_GUIDED_THR_PASS || g.fence_action == FENCE_ACTION_RTL) && (control_mode == GUIDED || control_mode == AVOID_ADSB) && geofence_present() && geofence_state->boundary_uptodate && geofence_state->old_switch_position == oldSwitchPosition && guided_WP_loc.lat == geofence_state->guided_lat && guided_WP_loc.lng == geofence_state->guided_lng) { geofence_state->old_switch_position = 254; set_mode(get_previous_mode(), MODE_REASON_GCS_COMMAND); } return; } /* allocate the geo-fence state if need be */ if (geofence_state == nullptr || !geofence_state->boundary_uptodate) { geofence_load(); if (!geofence_enabled()) { // may have been disabled by load return; } } bool outside = false; uint8_t breach_type = FENCE_BREACH_NONE; struct Location loc; // Never trigger a fence breach in the final stage of landing if (landing.is_expecting_impact()) { return; } if (geofence_state->floor_enabled && geofence_check_minalt()) { outside = true; breach_type = FENCE_BREACH_MINALT; } else if (geofence_check_maxalt()) { outside = true; breach_type = FENCE_BREACH_MAXALT; } else if (!altitude_check_only && ahrs.get_position(loc)) { Vector2l location; location.x = loc.lat; location.y = loc.lng; outside = Polygon_outside(location, &geofence_state->boundary[1], geofence_state->num_points-1); if (outside) { breach_type = FENCE_BREACH_BOUNDARY; } } if (!outside) { if (geofence_state->fence_triggered && !altitude_check_only) { // we have moved back inside the fence geofence_state->fence_triggered = false; gcs_send_text(MAV_SEVERITY_INFO,"Geofence OK"); #if FENCE_TRIGGERED_PIN > 0 hal.gpio->pinMode(FENCE_TRIGGERED_PIN, HAL_GPIO_OUTPUT); hal.gpio->write(FENCE_TRIGGERED_PIN, 0); #endif gcs_send_message(MSG_FENCE_STATUS); } // we're inside, all is good with the world return; } // we are outside the fence if (geofence_state->fence_triggered && (control_mode == GUIDED || control_mode == AVOID_ADSB || control_mode == RTL || g.fence_action == FENCE_ACTION_REPORT)) { // we have already triggered, don't trigger again until the // user disables/re-enables using the fence channel switch return; } // we are outside, and have not previously triggered. geofence_state->fence_triggered = true; geofence_state->breach_count++; geofence_state->breach_time = millis(); geofence_state->breach_type = breach_type; #if FENCE_TRIGGERED_PIN > 0 hal.gpio->pinMode(FENCE_TRIGGERED_PIN, HAL_GPIO_OUTPUT); hal.gpio->write(FENCE_TRIGGERED_PIN, 1); #endif gcs_send_text(MAV_SEVERITY_NOTICE,"Geofence triggered"); gcs_send_message(MSG_FENCE_STATUS); // see what action the user wants switch (g.fence_action) { case FENCE_ACTION_REPORT: break; case FENCE_ACTION_GUIDED: case FENCE_ACTION_GUIDED_THR_PASS: case FENCE_ACTION_RTL: // make sure we don't auto trim the surfaces on this mode change int8_t saved_auto_trim = g.auto_trim; g.auto_trim.set(0); if (g.fence_action == FENCE_ACTION_RTL) { set_mode(RTL, MODE_REASON_FENCE_BREACH); } else { set_mode(GUIDED, MODE_REASON_FENCE_BREACH); } g.auto_trim.set(saved_auto_trim); if (g.fence_ret_rally != 0 || g.fence_action == FENCE_ACTION_RTL) { //return to a rally point guided_WP_loc = rally.calc_best_rally_or_home_location(current_loc, get_RTL_altitude()); } else { //return to fence return point, not a rally point if (g.fence_retalt > 0) { //fly to the return point using fence_retalt guided_WP_loc.alt = home.alt + 100.0f*g.fence_retalt; } else if (g.fence_minalt >= g.fence_maxalt) { // invalid min/max, use RTL_altitude guided_WP_loc.alt = home.alt + g.RTL_altitude_cm; } else { // fly to the return point, with an altitude half way between // min and max guided_WP_loc.alt = home.alt + 100.0f*(g.fence_minalt + g.fence_maxalt)/2; } guided_WP_loc.options = 0; guided_WP_loc.lat = geofence_state->boundary[0].x; guided_WP_loc.lng = geofence_state->boundary[0].y; } geofence_state->guided_lat = guided_WP_loc.lat; geofence_state->guided_lng = guided_WP_loc.lng; geofence_state->old_switch_position = oldSwitchPosition; if (g.fence_action != FENCE_ACTION_RTL) { //not needed for RTL mode setup_terrain_target_alt(guided_WP_loc); set_guided_WP(); } if (g.fence_action == FENCE_ACTION_GUIDED_THR_PASS) { guided_throttle_passthru = true; } break; } }
// update error mask of sensors and subsystems. The mask // uses the MAV_SYS_STATUS_* values from mavlink. If a bit is set // then it indicates that the sensor or subsystem is present but // not functioning correctly. void Plane::update_sensor_status_flags(void) { // 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 (airspeed.enabled()) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE; } if (gps.status() > AP_GPS::NO_GPS) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS; } #if OPTFLOW == ENABLED if (optflow.enabled()) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW; } #endif if (geofence_present()) { control_sensors_present |= MAV_SYS_STATUS_GEOFENCE; } if (aparm.throttle_min < 0) { control_sensors_present |= MAV_SYS_STATUS_REVERSE_MOTOR; } if (plane.DataFlash.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, geofence and motor output which we will set individually control_sensors_enabled = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL & ~MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION & ~MAV_SYS_STATUS_SENSOR_YAW_POSITION & ~MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL & ~MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL & ~MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS & ~MAV_SYS_STATUS_GEOFENCE & ~MAV_SYS_STATUS_LOGGING); if (airspeed.enabled() && airspeed.use()) { control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE; } if (geofence_enabled()) { control_sensors_enabled |= MAV_SYS_STATUS_GEOFENCE; } if (plane.DataFlash.logging_enabled()) { control_sensors_enabled |= MAV_SYS_STATUS_LOGGING; } switch (control_mode) { case MANUAL: break; case ACRO: control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL; // 3D angular rate control break; case STABILIZE: case FLY_BY_WIRE_A: case AUTOTUNE: case QSTABILIZE: case QHOVER: case QLAND: case QLOITER: control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL; // 3D angular rate control control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION; // attitude stabilisation break; case FLY_BY_WIRE_B: case CRUISE: control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL; // 3D angular rate control control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION; // attitude stabilisation break; case TRAINING: if (!training_manual_roll || !training_manual_pitch) { control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL; // 3D angular rate control control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION; // attitude stabilisation } break; case AUTO: case RTL: case LOITER: case AVOID_ADSB: case GUIDED: case CIRCLE: case QRTL: control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL; // 3D angular rate control control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION; // attitude stabilisation control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_YAW_POSITION; // yaw position control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; // altitude control control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; // X/Y position control break; case INITIALISING: break; } // 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; } // default: all present sensors healthy except baro, 3D_MAG, GPS, DIFFERNTIAL_PRESSURE. GEOFENCE always defaults to healthy. control_sensors_health = control_sensors_present & ~(MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE | MAV_SYS_STATUS_SENSOR_3D_MAG | MAV_SYS_STATUS_SENSOR_GPS | MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE); control_sensors_health |= MAV_SYS_STATUS_GEOFENCE; if (ahrs.initialised() && !ahrs.healthy()) { // AHRS subsystem is unhealthy control_sensors_health &= ~MAV_SYS_STATUS_AHRS; } if (ahrs.have_inertial_nav() && !ins.accel_calibrated_ok_all()) { // trying to use EKF without properly calibrated accelerometers control_sensors_health &= ~MAV_SYS_STATUS_AHRS; } if (barometer.all_healthy()) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE; } if (g.compass_enabled && compass.healthy(0) && ahrs.use_compass()) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG; } if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS; } #if OPTFLOW == ENABLED if (optflow.healthy()) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW; } #endif 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 (airspeed.healthy()) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE; } #if GEOFENCE_ENABLED if (geofence_breached()) { control_sensors_health &= ~MAV_SYS_STATUS_GEOFENCE; } #endif if (plane.DataFlash.logging_failed()) { control_sensors_health &= ~MAV_SYS_STATUS_LOGGING; } if (millis() - failsafe.last_valid_rc_ms < 200) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER; } else { control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_RC_RECEIVER; } #if AP_TERRAIN_AVAILABLE switch (terrain.status()) { case AP_Terrain::TerrainStatusDisabled: break; case AP_Terrain::TerrainStatusUnhealthy: control_sensors_present |= MAV_SYS_STATUS_TERRAIN; control_sensors_enabled |= MAV_SYS_STATUS_TERRAIN; break; case AP_Terrain::TerrainStatusOK: control_sensors_present |= MAV_SYS_STATUS_TERRAIN; control_sensors_enabled |= MAV_SYS_STATUS_TERRAIN; control_sensors_health |= MAV_SYS_STATUS_TERRAIN; break; } #endif #if RANGEFINDER_ENABLED == ENABLED if (rangefinder.num_sensors() > 0) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION; if (g.rangefinder_landing) { control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION; } if (rangefinder.has_data()) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION; } } #endif if (aparm.throttle_min < 0 && channel_throttle->get_servo_out() < 0) { control_sensors_enabled |= MAV_SYS_STATUS_REVERSE_MOTOR; control_sensors_health |= MAV_SYS_STATUS_REVERSE_MOTOR; } if (AP_Notify::flags.initialising) { // 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); } #if FRSKY_TELEM_ENABLED == ENABLED // give mask of error flags to Frsky_Telemetry frsky_telemetry.update_sensor_status_flags(~control_sensors_health & control_sensors_enabled & control_sensors_present); #endif }