2015-05-29 23:12:49 -03:00
|
|
|
#include "Copter.h"
|
|
|
|
|
|
|
|
void Copter::init_barometer(bool full_calibration)
|
2010-12-19 12:40:33 -04:00
|
|
|
{
|
2017-07-08 21:56:49 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Calibrating barometer");
|
2014-01-15 10:18:23 -04:00
|
|
|
if (full_calibration) {
|
|
|
|
barometer.calibrate();
|
|
|
|
}else{
|
|
|
|
barometer.update_calibration();
|
|
|
|
}
|
2017-07-08 21:56:49 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Barometer calibration complete");
|
2011-02-25 01:33:39 -04:00
|
|
|
}
|
2011-12-26 19:13:47 -04:00
|
|
|
|
2012-06-20 02:17:15 -03:00
|
|
|
// return barometric altitude in centimeters
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::read_barometer(void)
|
2011-02-21 00:30:56 -04:00
|
|
|
{
|
2015-01-05 07:28:00 -04:00
|
|
|
barometer.update();
|
2014-10-16 21:37:49 -03:00
|
|
|
if (should_log(MASK_LOG_IMU)) {
|
2014-02-18 16:38:20 -04:00
|
|
|
Log_Write_Baro();
|
|
|
|
}
|
2014-10-22 04:07:10 -03:00
|
|
|
baro_alt = barometer.get_altitude() * 100.0f;
|
|
|
|
baro_climbrate = barometer.get_climb_rate() * 100.0f;
|
2015-04-22 22:19:44 -03:00
|
|
|
|
2017-01-09 03:31:26 -04:00
|
|
|
motors->set_air_density_ratio(barometer.get_air_density_ratio());
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
|
|
|
|
2016-04-27 08:37:04 -03:00
|
|
|
void Copter::init_rangefinder(void)
|
2014-10-31 08:40:24 -03:00
|
|
|
{
|
2016-04-27 08:37:04 -03:00
|
|
|
#if RANGEFINDER_ENABLED == ENABLED
|
|
|
|
rangefinder.init();
|
2016-04-28 00:30:41 -03:00
|
|
|
rangefinder_state.alt_cm_filt.set_cutoff_frequency(RANGEFINDER_WPNAV_FILT_HZ);
|
2017-02-09 07:30:59 -04:00
|
|
|
rangefinder_state.enabled = rangefinder.has_orientation(ROTATION_PITCH_270);
|
2014-10-31 08:40:24 -03:00
|
|
|
#endif
|
2016-04-27 08:37:04 -03:00
|
|
|
}
|
2014-10-31 08:40:24 -03:00
|
|
|
|
2016-04-27 08:37:04 -03:00
|
|
|
// return rangefinder altitude in centimeters
|
2016-04-27 09:20:03 -03:00
|
|
|
void Copter::read_rangefinder(void)
|
2012-12-21 01:03:47 -04:00
|
|
|
{
|
2016-04-27 07:55:35 -03:00
|
|
|
#if RANGEFINDER_ENABLED == ENABLED
|
2016-04-27 08:37:04 -03:00
|
|
|
rangefinder.update();
|
2014-06-27 01:23:56 -03:00
|
|
|
|
2016-11-20 01:11:57 -04:00
|
|
|
if (rangefinder.num_sensors() > 0 &&
|
|
|
|
should_log(MASK_LOG_CTUN)) {
|
|
|
|
DataFlash.Log_Write_RFND(rangefinder);
|
|
|
|
}
|
2012-12-21 01:03:47 -04:00
|
|
|
|
2017-02-09 07:30:59 -04:00
|
|
|
rangefinder_state.alt_healthy = ((rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::RangeFinder_Good) && (rangefinder.range_valid_count_orient(ROTATION_PITCH_270) >= RANGEFINDER_HEALTH_MAX));
|
|
|
|
|
|
|
|
int16_t temp_alt = rangefinder.distance_cm_orient(ROTATION_PITCH_270);
|
2012-12-29 00:51:14 -04:00
|
|
|
|
2016-04-28 00:32:46 -03:00
|
|
|
#if RANGEFINDER_TILT_CORRECTION == ENABLED
|
2016-04-27 08:37:04 -03:00
|
|
|
// correct alt for angle of the rangefinder
|
2016-04-28 00:32:46 -03:00
|
|
|
temp_alt = (float)temp_alt * MAX(0.707f, ahrs.get_rotation_body_to_ned().c.z);
|
2012-12-21 01:03:47 -04:00
|
|
|
#endif
|
|
|
|
|
2016-05-07 04:55:40 -03:00
|
|
|
rangefinder_state.alt_cm = temp_alt;
|
2016-04-28 00:30:41 -03:00
|
|
|
|
|
|
|
// filter rangefinder for use by AC_WPNav
|
|
|
|
uint32_t now = AP_HAL::millis();
|
|
|
|
|
|
|
|
if (rangefinder_state.alt_healthy) {
|
|
|
|
if (now - rangefinder_state.last_healthy_ms > RANGEFINDER_TIMEOUT_MS) {
|
|
|
|
// reset filter if we haven't used it within the last second
|
|
|
|
rangefinder_state.alt_cm_filt.reset(rangefinder_state.alt_cm);
|
|
|
|
} else {
|
2016-05-20 22:19:53 -03:00
|
|
|
rangefinder_state.alt_cm_filt.apply(rangefinder_state.alt_cm, 0.05f);
|
2016-04-28 00:30:41 -03:00
|
|
|
}
|
|
|
|
rangefinder_state.last_healthy_ms = now;
|
|
|
|
}
|
|
|
|
|
|
|
|
// send rangefinder altitude and health to waypoint navigation library
|
2017-01-09 03:31:26 -04:00
|
|
|
wp_nav->set_rangefinder_alt(rangefinder_state.enabled, rangefinder_state.alt_healthy, rangefinder_state.alt_cm_filt.get());
|
2016-04-28 00:30:41 -03:00
|
|
|
|
2012-12-21 01:03:47 -04:00
|
|
|
#else
|
2016-05-11 03:31:58 -03:00
|
|
|
rangefinder_state.enabled = false;
|
2016-05-07 04:55:40 -03:00
|
|
|
rangefinder_state.alt_healthy = false;
|
|
|
|
rangefinder_state.alt_cm = 0;
|
2012-12-21 01:03:47 -04:00
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2016-04-27 09:18:35 -03:00
|
|
|
// return true if rangefinder_alt can be used
|
|
|
|
bool Copter::rangefinder_alt_ok()
|
|
|
|
{
|
2016-05-07 04:55:40 -03:00
|
|
|
return (rangefinder_state.enabled && rangefinder_state.alt_healthy);
|
2016-04-27 09:18:35 -03:00
|
|
|
}
|
|
|
|
|
2015-08-07 02:34:56 -03:00
|
|
|
/*
|
|
|
|
update RPM sensors
|
|
|
|
*/
|
|
|
|
void Copter::rpm_update(void)
|
|
|
|
{
|
|
|
|
rpm_sensor.update();
|
2015-11-19 22:06:14 -04:00
|
|
|
if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) {
|
2015-08-07 07:34:27 -03:00
|
|
|
if (should_log(MASK_LOG_RCIN)) {
|
|
|
|
DataFlash.Log_Write_RPM(rpm_sensor);
|
|
|
|
}
|
|
|
|
}
|
2015-08-07 02:34:56 -03:00
|
|
|
}
|
|
|
|
|
2014-10-31 08:40:24 -03:00
|
|
|
// initialise compass
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::init_compass()
|
2011-12-29 23:06:31 -04:00
|
|
|
{
|
2017-06-06 22:27:42 -03:00
|
|
|
if (!g.compass_enabled) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
if (!compass.init() || !compass.read()) {
|
2012-02-24 23:09:12 -04:00
|
|
|
// make sure we don't pass a broken compass to DCM
|
2017-01-21 00:34:19 -04:00
|
|
|
cliSerial->printf("COMPASS INIT ERROR\n");
|
2012-12-29 23:08:25 -04:00
|
|
|
Log_Write_Error(ERROR_SUBSYSTEM_COMPASS,ERROR_CODE_FAILED_TO_INITIALISE);
|
2012-02-24 23:09:12 -04:00
|
|
|
return;
|
|
|
|
}
|
2012-03-11 05:36:12 -03:00
|
|
|
ahrs.set_compass(&compass);
|
2011-12-29 23:06:31 -04:00
|
|
|
}
|
|
|
|
|
2017-06-05 04:52:31 -03:00
|
|
|
/*
|
|
|
|
if the compass is enabled then try to accumulate a reading
|
|
|
|
also update initial location used for declination
|
|
|
|
*/
|
|
|
|
void Copter::compass_accumulate(void)
|
|
|
|
{
|
|
|
|
if (!g.compass_enabled) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
compass.accumulate();
|
|
|
|
|
|
|
|
// update initial location used for declination
|
|
|
|
if (!ap.compass_init_location) {
|
|
|
|
Location loc;
|
|
|
|
if (ahrs.get_position(loc)) {
|
|
|
|
compass.set_initial_location(loc.lat, loc.lng);
|
|
|
|
ap.compass_init_location = true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2014-10-31 08:40:24 -03:00
|
|
|
// initialise optical flow sensor
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::init_optflow()
|
2011-12-29 23:06:31 -04:00
|
|
|
{
|
2012-11-18 12:16:07 -04:00
|
|
|
#if OPTFLOW == ENABLED
|
2014-07-11 23:34:55 -03:00
|
|
|
// exit immediately if not enabled
|
|
|
|
if (!optflow.enabled()) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2015-04-23 04:24:31 -03:00
|
|
|
// initialise optical flow sensor
|
2014-01-08 23:29:50 -04:00
|
|
|
optflow.init();
|
2012-11-18 12:16:07 -04:00
|
|
|
#endif // OPTFLOW == ENABLED
|
2011-12-29 23:06:31 -04:00
|
|
|
}
|
|
|
|
|
2014-12-07 21:29:32 -04:00
|
|
|
// called at 200hz
|
|
|
|
#if OPTFLOW == ENABLED
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::update_optical_flow(void)
|
2014-12-07 21:29:32 -04:00
|
|
|
{
|
|
|
|
static uint32_t last_of_update = 0;
|
|
|
|
|
|
|
|
// exit immediately if not enabled
|
|
|
|
if (!optflow.enabled()) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// read from sensor
|
|
|
|
optflow.update();
|
|
|
|
|
|
|
|
// write to log and send to EKF if new data has arrived
|
|
|
|
if (optflow.last_update() != last_of_update) {
|
|
|
|
last_of_update = optflow.last_update();
|
|
|
|
uint8_t flowQuality = optflow.quality();
|
|
|
|
Vector2f flowRate = optflow.flowRate();
|
|
|
|
Vector2f bodyRate = optflow.bodyRate();
|
2016-10-27 01:47:50 -03:00
|
|
|
const Vector3f &posOffset = optflow.get_pos_offset();
|
2016-10-11 18:24:25 -03:00
|
|
|
ahrs.writeOptFlowMeas(flowQuality, flowRate, bodyRate, last_of_update, posOffset);
|
2015-01-05 22:06:44 -04:00
|
|
|
if (g.log_bitmask & MASK_LOG_OPTFLOW) {
|
2014-12-07 21:29:32 -04:00
|
|
|
Log_Write_Optflow();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif // OPTFLOW == ENABLED
|
|
|
|
|
2012-11-13 10:43:54 -04:00
|
|
|
// read_battery - check battery voltage and current and invoke failsafe if necessary
|
|
|
|
// called at 10hz
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::read_battery(void)
|
2010-12-19 12:40:33 -04:00
|
|
|
{
|
2013-10-01 10:34:44 -03:00
|
|
|
battery.read();
|
2011-01-17 22:48:44 -04:00
|
|
|
|
2013-10-01 10:34:44 -03:00
|
|
|
// update compass with current value
|
2014-12-03 01:32:44 -04:00
|
|
|
if (battery.has_current()) {
|
2013-10-01 10:34:44 -03:00
|
|
|
compass.set_current(battery.current_amps());
|
2012-08-16 21:50:03 -03:00
|
|
|
}
|
2015-02-11 07:50:55 -04:00
|
|
|
|
|
|
|
// update motors with voltage and current
|
|
|
|
if (battery.get_type() != AP_BattMonitor::BattMonitor_TYPE_NONE) {
|
2017-01-09 03:31:26 -04:00
|
|
|
motors->set_voltage(battery.voltage());
|
2017-01-20 01:37:07 -04:00
|
|
|
AP_Notify::flags.battery_voltage = battery.voltage();
|
2015-02-11 07:50:55 -04:00
|
|
|
}
|
|
|
|
if (battery.has_current()) {
|
2017-01-09 03:31:26 -04:00
|
|
|
motors->set_current(battery.current_amps());
|
2017-05-23 04:14:26 -03:00
|
|
|
motors->set_resistance(battery.get_resistance());
|
|
|
|
motors->set_voltage_resting_estimate(battery.voltage_resting_estimate());
|
2015-02-11 07:50:55 -04:00
|
|
|
}
|
2012-08-16 21:50:03 -03:00
|
|
|
|
2012-11-13 10:43:54 -04:00
|
|
|
// check for low voltage or current if the low voltage check hasn't already been triggered
|
2013-09-12 10:41:28 -03:00
|
|
|
// we only check when we're not powered by USB to avoid false alarms during bench tests
|
2013-10-13 01:52:52 -03:00
|
|
|
if (!ap.usb_connected && !failsafe.battery && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah)) {
|
|
|
|
failsafe_battery_event();
|
2012-08-16 21:50:03 -03:00
|
|
|
}
|
2014-10-07 09:40:48 -03:00
|
|
|
|
|
|
|
// log battery info to the dataflash
|
2014-10-16 21:37:49 -03:00
|
|
|
if (should_log(MASK_LOG_CURRENT)) {
|
2014-10-07 09:40:48 -03:00
|
|
|
Log_Write_Current();
|
|
|
|
}
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
2012-11-22 05:59:33 -04:00
|
|
|
|
|
|
|
// read the receiver RSSI as an 8 bit number for MAVLink
|
|
|
|
// RC_CHANNELS_SCALED message
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::read_receiver_rssi(void)
|
2012-11-22 05:59:33 -04:00
|
|
|
{
|
2015-08-28 03:00:55 -03:00
|
|
|
receiver_rssi = rssi.read_receiver_rssi_uint8();
|
2012-11-22 05:59:33 -04:00
|
|
|
}
|
2014-09-15 03:52:21 -03:00
|
|
|
|
2015-07-01 16:36:53 -03:00
|
|
|
void Copter::compass_cal_update()
|
|
|
|
{
|
2016-09-27 17:33:56 -03:00
|
|
|
static uint32_t compass_cal_stick_gesture_begin = 0;
|
|
|
|
|
2015-07-01 16:36:53 -03:00
|
|
|
if (!hal.util->get_soft_armed()) {
|
|
|
|
compass.compass_cal_update();
|
|
|
|
}
|
2016-09-27 17:33:56 -03:00
|
|
|
|
|
|
|
if (compass.is_calibrating()) {
|
|
|
|
if (channel_yaw->get_control_in() < -4000 && channel_throttle->get_control_in() > 900) {
|
|
|
|
compass.cancel_calibration_all();
|
|
|
|
}
|
|
|
|
} else {
|
2017-01-09 03:31:26 -04:00
|
|
|
bool stick_gesture_detected = compass_cal_stick_gesture_begin != 0 && !motors->armed() && channel_yaw->get_control_in() > 4000 && channel_throttle->get_control_in() > 900;
|
2016-09-27 17:33:56 -03:00
|
|
|
uint32_t tnow = millis();
|
|
|
|
|
|
|
|
if (!stick_gesture_detected) {
|
|
|
|
compass_cal_stick_gesture_begin = tnow;
|
|
|
|
} else if (tnow-compass_cal_stick_gesture_begin > 1000*COMPASS_CAL_STICK_GESTURE_TIME) {
|
2016-10-25 02:19:18 -03:00
|
|
|
#ifdef CAL_ALWAYS_REBOOT
|
|
|
|
compass.start_calibration_all(true,true,COMPASS_CAL_STICK_DELAY,true);
|
|
|
|
#else
|
2016-09-27 17:33:56 -03:00
|
|
|
compass.start_calibration_all(true,true,COMPASS_CAL_STICK_DELAY,false);
|
2016-10-25 02:19:18 -03:00
|
|
|
#endif
|
2016-09-27 17:33:56 -03:00
|
|
|
}
|
|
|
|
}
|
2015-07-01 16:36:53 -03:00
|
|
|
}
|
|
|
|
|
2015-10-16 19:05:53 -03:00
|
|
|
void Copter::accel_cal_update()
|
|
|
|
{
|
|
|
|
if (hal.util->get_soft_armed()) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
ins.acal_update();
|
|
|
|
// check if new trim values, and set them
|
|
|
|
float trim_roll, trim_pitch;
|
|
|
|
if(ins.get_new_trim(trim_roll, trim_pitch)) {
|
|
|
|
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
|
|
|
|
}
|
2016-01-05 20:23:16 -04:00
|
|
|
|
|
|
|
#ifdef CAL_ALWAYS_REBOOT
|
|
|
|
if (ins.accel_cal_requires_reboot()) {
|
|
|
|
hal.scheduler->delay(1000);
|
|
|
|
hal.scheduler->reboot(false);
|
|
|
|
}
|
|
|
|
#endif
|
2015-10-16 19:05:53 -03:00
|
|
|
}
|
|
|
|
|
2016-10-28 19:08:22 -03:00
|
|
|
#if GRIPPER_ENABLED == ENABLED
|
|
|
|
// gripper update
|
|
|
|
void Copter::gripper_update()
|
|
|
|
{
|
|
|
|
g2.gripper.update();
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2016-07-21 22:24:13 -03:00
|
|
|
/*
|
|
|
|
update AP_Button
|
|
|
|
*/
|
|
|
|
void Copter::button_update(void)
|
|
|
|
{
|
|
|
|
g2.button.update();
|
|
|
|
}
|
2016-08-15 03:53:45 -03:00
|
|
|
|
|
|
|
// initialise proximity sensor
|
|
|
|
void Copter::init_proximity(void)
|
|
|
|
{
|
|
|
|
#if PROXIMITY_ENABLED == ENABLED
|
2016-10-14 02:02:29 -03:00
|
|
|
g2.proximity.init();
|
2017-02-09 07:30:59 -04:00
|
|
|
g2.proximity.set_rangefinder(&rangefinder);
|
2016-08-15 03:53:45 -03:00
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
|
|
|
// update proximity sensor
|
|
|
|
void Copter::update_proximity(void)
|
|
|
|
{
|
|
|
|
#if PROXIMITY_ENABLED == ENABLED
|
2016-10-14 02:02:29 -03:00
|
|
|
g2.proximity.update();
|
2016-08-15 03:53:45 -03:00
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2016-09-20 16:42:24 -03:00
|
|
|
// 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 Copter::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 (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 PRECISION_LANDING == ENABLED
|
|
|
|
if (precland.enabled()) {
|
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
|
|
|
}
|
2017-03-01 07:18:11 -04:00
|
|
|
#endif
|
|
|
|
#if VISUAL_ODOMETRY_ENABLED == ENABLED
|
|
|
|
if (g2.visual_odom.enabled()) {
|
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
|
|
|
}
|
2016-09-20 16:42:24 -03:00
|
|
|
#endif
|
|
|
|
if (ap.rc_receiver_present) {
|
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
|
|
|
}
|
|
|
|
if (copter.DataFlash.logging_present()) { // primary logging only (usually File)
|
|
|
|
control_sensors_present |= MAV_SYS_STATUS_LOGGING;
|
|
|
|
}
|
|
|
|
#if PROXIMITY_ENABLED == ENABLED
|
|
|
|
if (copter.g2.proximity.get_status() > AP_Proximity::Proximity_NotConnected) {
|
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
|
|
|
}
|
|
|
|
#endif
|
2017-01-19 21:51:35 -04:00
|
|
|
if (copter.battery.healthy()) {
|
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_BATTERY;
|
|
|
|
}
|
|
|
|
|
2016-09-20 16:42:24 -03:00
|
|
|
|
|
|
|
// all present sensors enabled by default except altitude and position control and motors which we will set individually
|
|
|
|
control_sensors_enabled = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL &
|
|
|
|
~MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL &
|
|
|
|
~MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS &
|
2017-01-19 21:51:35 -04:00
|
|
|
~MAV_SYS_STATUS_LOGGING &
|
|
|
|
~MAV_SYS_STATUS_SENSOR_BATTERY);
|
2016-09-20 16:42:24 -03:00
|
|
|
|
|
|
|
switch (control_mode) {
|
|
|
|
case AUTO:
|
|
|
|
case AVOID_ADSB:
|
|
|
|
case GUIDED:
|
|
|
|
case LOITER:
|
|
|
|
case RTL:
|
|
|
|
case CIRCLE:
|
|
|
|
case LAND:
|
|
|
|
case POSHOLD:
|
|
|
|
case BRAKE:
|
|
|
|
case THROW:
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
|
|
|
|
break;
|
|
|
|
case ALT_HOLD:
|
|
|
|
case GUIDED_NOGPS:
|
|
|
|
case SPORT:
|
|
|
|
case AUTOTUNE:
|
|
|
|
control_sensors_enabled |= 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;
|
|
|
|
}
|
|
|
|
|
|
|
|
// 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 (copter.DataFlash.logging_enabled()) {
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_LOGGING;
|
|
|
|
}
|
|
|
|
|
2017-01-19 21:51:35 -04:00
|
|
|
if (g.fs_batt_voltage > 0 || g.fs_batt_mah > 0) {
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_BATTERY;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2016-09-20 16:42:24 -03:00
|
|
|
|
|
|
|
// default to all healthy
|
|
|
|
control_sensors_health = control_sensors_present;
|
|
|
|
|
|
|
|
if (!barometer.all_healthy()) {
|
|
|
|
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
|
|
|
}
|
|
|
|
if (!g.compass_enabled || !compass.healthy() || !ahrs.use_compass()) {
|
|
|
|
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_MAG;
|
|
|
|
}
|
|
|
|
if (gps.status() == AP_GPS::NO_GPS) {
|
|
|
|
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_GPS;
|
|
|
|
}
|
|
|
|
if (!ap.rc_receiver_present || failsafe.radio) {
|
|
|
|
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
|
|
|
}
|
|
|
|
#if OPTFLOW == ENABLED
|
|
|
|
if (!optflow.healthy()) {
|
|
|
|
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
#if PRECISION_LANDING == ENABLED
|
2017-03-01 07:18:11 -04:00
|
|
|
if (precland.enabled() && !precland.healthy()) {
|
|
|
|
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
#if VISUAL_ODOMETRY_ENABLED == ENABLED
|
|
|
|
if (g2.visual_odom.enabled() && !g2.visual_odom.healthy()) {
|
2016-09-20 16:42:24 -03:00
|
|
|
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
|
|
|
}
|
|
|
|
#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 (ahrs.initialised() && !ahrs.healthy()) {
|
|
|
|
// AHRS subsystem is unhealthy
|
|
|
|
control_sensors_health &= ~MAV_SYS_STATUS_AHRS;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (copter.DataFlash.logging_failed()) {
|
|
|
|
control_sensors_health &= ~MAV_SYS_STATUS_LOGGING;
|
|
|
|
}
|
|
|
|
|
|
|
|
#if PROXIMITY_ENABLED == ENABLED
|
|
|
|
if (copter.g2.proximity.get_status() < AP_Proximity::Proximity_Good) {
|
|
|
|
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
|
|
|
switch (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
|
|
|
|
|
|
|
|
#if RANGEFINDER_ENABLED == ENABLED
|
2017-02-09 07:30:59 -04:00
|
|
|
if (rangefinder_state.enabled) {
|
2016-09-20 16:42:24 -03:00
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
2017-02-09 07:30:59 -04:00
|
|
|
if (rangefinder.has_data_orient(ROTATION_PITCH_270)) {
|
2016-09-20 16:42:24 -03:00
|
|
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
if (!ap.initialised || 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);
|
|
|
|
}
|
2017-01-19 21:51:35 -04:00
|
|
|
|
|
|
|
if (copter.failsafe.battery) {
|
|
|
|
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_BATTERY; }
|
2016-09-20 16:42:24 -03:00
|
|
|
|
|
|
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
|
|
|
// give mask of error flags to Frsky_Telemetry
|
2016-10-29 16:45:31 -03:00
|
|
|
frsky_telemetry.update_sensor_status_flags(~control_sensors_health & control_sensors_enabled & control_sensors_present);
|
2016-09-20 16:42:24 -03:00
|
|
|
#endif
|
|
|
|
}
|
2016-10-24 02:46:33 -03:00
|
|
|
|
|
|
|
// init beacons used for non-gps position estimates
|
|
|
|
void Copter::init_beacon()
|
|
|
|
{
|
|
|
|
g2.beacon.init();
|
|
|
|
}
|
|
|
|
|
|
|
|
// update beacons
|
|
|
|
void Copter::update_beacon()
|
|
|
|
{
|
|
|
|
g2.beacon.update();
|
|
|
|
}
|
2017-03-01 07:18:11 -04:00
|
|
|
|
|
|
|
// init visual odometry sensor
|
|
|
|
void Copter::init_visual_odom()
|
|
|
|
{
|
|
|
|
#if VISUAL_ODOMETRY_ENABLED == ENABLED
|
|
|
|
g2.visual_odom.init();
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
|
|
|
// update visual odometry sensor
|
|
|
|
void Copter::update_visual_odom()
|
|
|
|
{
|
|
|
|
#if VISUAL_ODOMETRY_ENABLED == ENABLED
|
|
|
|
// check for updates
|
|
|
|
if (g2.visual_odom.enabled() && (g2.visual_odom.get_last_update_ms() != visual_odom_last_update_ms)) {
|
|
|
|
visual_odom_last_update_ms = g2.visual_odom.get_last_update_ms();
|
|
|
|
float time_delta_sec = g2.visual_odom.get_time_delta_usec() / 1000000.0f;
|
|
|
|
ahrs.writeBodyFrameOdom(g2.visual_odom.get_confidence(),
|
|
|
|
g2.visual_odom.get_position_delta(),
|
|
|
|
g2.visual_odom.get_angle_delta(),
|
|
|
|
time_delta_sec,
|
|
|
|
visual_odom_last_update_ms,
|
|
|
|
g2.visual_odom.get_pos_offset());
|
|
|
|
// log sensor data
|
|
|
|
DataFlash.Log_Write_VisualOdom(time_delta_sec,
|
|
|
|
g2.visual_odom.get_angle_delta(),
|
|
|
|
g2.visual_odom.get_position_delta(),
|
|
|
|
g2.visual_odom.get_confidence());
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
}
|