#include "GCS_Copter.h" #include "Copter.h" uint8_t GCS_Copter::sysid_this_mav() const { return copter.g.sysid_this_mav; } const char* GCS_Copter::frame_string() const { if (copter.motors == nullptr) { return "MultiCopter"; } return copter.motors->get_frame_string(); } bool GCS_Copter::simple_input_active() const { return copter.simple_mode == Copter::SimpleMode::SIMPLE; } bool GCS_Copter::supersimple_input_active() const { return copter.simple_mode == Copter::SimpleMode::SUPERSIMPLE; } void GCS_Copter::update_vehicle_sensor_status_flags(void) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL | MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION | MAV_SYS_STATUS_SENSOR_YAW_POSITION; control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL | MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION | MAV_SYS_STATUS_SENSOR_YAW_POSITION; control_sensors_health |= MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL | MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION | MAV_SYS_STATUS_SENSOR_YAW_POSITION; // update flightmode-specific flags: control_sensors_present |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; control_sensors_present |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; switch (copter.flightmode->mode_number()) { case Mode::Number::AUTO: case Mode::Number::AUTO_RTL: case Mode::Number::AVOID_ADSB: case Mode::Number::GUIDED: case Mode::Number::LOITER: case Mode::Number::RTL: case Mode::Number::CIRCLE: case Mode::Number::LAND: case Mode::Number::POSHOLD: case Mode::Number::BRAKE: case Mode::Number::THROW: case Mode::Number::SMART_RTL: control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; control_sensors_health |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; control_sensors_health |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; break; case Mode::Number::ALT_HOLD: case Mode::Number::GUIDED_NOGPS: case Mode::Number::SPORT: case Mode::Number::AUTOTUNE: case Mode::Number::FLOWHOLD: control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; control_sensors_health |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; break; default: // stabilize, acro, drift, and flip have no automatic x,y or z control (i.e. all manual) break; } // optional sensors, some of which are essentially always // available in the firmware: #if HAL_PROXIMITY_ENABLED if (copter.g2.proximity.sensor_present()) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_PROXIMITY; } if (copter.g2.proximity.sensor_enabled()) { control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_PROXIMITY; } if (!copter.g2.proximity.sensor_failed()) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_PROXIMITY; } #endif #if RANGEFINDER_ENABLED == ENABLED const RangeFinder *rangefinder = RangeFinder::get_singleton(); if (rangefinder && rangefinder->has_orientation(ROTATION_PITCH_270)) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION; } if (copter.rangefinder_state.enabled) { control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION; if (rangefinder && rangefinder->has_data_orient(ROTATION_PITCH_270)) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION; } } #endif #if AC_PRECLAND_ENABLED if (copter.precland.enabled()) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION; control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_VISION_POSITION; } if (copter.precland.enabled() && copter.precland.healthy()) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_VISION_POSITION; } #endif #if AP_TERRAIN_AVAILABLE switch (copter.terrain.status()) { case AP_Terrain::TerrainStatusDisabled: break; case AP_Terrain::TerrainStatusUnhealthy: // To-Do: restore unhealthy terrain status reporting once terrain is used in copter //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 control_sensors_present |= MAV_SYS_STATUS_SENSOR_PROPULSION; control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_PROPULSION; // only mark propulsion healthy if all of the motors are producing // nominal thrust if (!copter.motors->get_thrust_boost()) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_PROPULSION; } }