|
|
@ -40,7 +40,7 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan) |
|
|
|
|
|
|
|
|
|
|
|
// check compass is enabled
|
|
|
|
// check compass is enabled
|
|
|
|
if (!g.compass_enabled) { |
|
|
|
if (!g.compass_enabled) { |
|
|
|
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "Compass disabled"); |
|
|
|
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "Compass disabled"); |
|
|
|
ap.compass_mot = false; |
|
|
|
ap.compass_mot = false; |
|
|
|
return MAV_RESULT_TEMPORARILY_REJECTED; |
|
|
|
return MAV_RESULT_TEMPORARILY_REJECTED; |
|
|
|
} |
|
|
|
} |
|
|
@ -49,7 +49,7 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan) |
|
|
|
compass.read(); |
|
|
|
compass.read(); |
|
|
|
for (uint8_t i=0; i<compass.get_count(); i++) { |
|
|
|
for (uint8_t i=0; i<compass.get_count(); i++) { |
|
|
|
if (!compass.healthy(i)) { |
|
|
|
if (!compass.healthy(i)) { |
|
|
|
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "Check compass"); |
|
|
|
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "Check compass"); |
|
|
|
ap.compass_mot = false; |
|
|
|
ap.compass_mot = false; |
|
|
|
return MAV_RESULT_TEMPORARILY_REJECTED; |
|
|
|
return MAV_RESULT_TEMPORARILY_REJECTED; |
|
|
|
} |
|
|
|
} |
|
|
@ -58,7 +58,7 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan) |
|
|
|
// check if radio is calibrated
|
|
|
|
// check if radio is calibrated
|
|
|
|
arming.pre_arm_rc_checks(true); |
|
|
|
arming.pre_arm_rc_checks(true); |
|
|
|
if (!ap.pre_arm_rc_check) { |
|
|
|
if (!ap.pre_arm_rc_check) { |
|
|
|
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "RC not calibrated"); |
|
|
|
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "RC not calibrated"); |
|
|
|
ap.compass_mot = false; |
|
|
|
ap.compass_mot = false; |
|
|
|
return MAV_RESULT_TEMPORARILY_REJECTED; |
|
|
|
return MAV_RESULT_TEMPORARILY_REJECTED; |
|
|
|
} |
|
|
|
} |
|
|
@ -66,14 +66,14 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan) |
|
|
|
// check throttle is at zero
|
|
|
|
// check throttle is at zero
|
|
|
|
read_radio(); |
|
|
|
read_radio(); |
|
|
|
if (channel_throttle->get_control_in() != 0) { |
|
|
|
if (channel_throttle->get_control_in() != 0) { |
|
|
|
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "Throttle not zero"); |
|
|
|
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "Throttle not zero"); |
|
|
|
ap.compass_mot = false; |
|
|
|
ap.compass_mot = false; |
|
|
|
return MAV_RESULT_TEMPORARILY_REJECTED; |
|
|
|
return MAV_RESULT_TEMPORARILY_REJECTED; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// check we are landed
|
|
|
|
// check we are landed
|
|
|
|
if (!ap.land_complete) { |
|
|
|
if (!ap.land_complete) { |
|
|
|
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "Not landed"); |
|
|
|
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "Not landed"); |
|
|
|
ap.compass_mot = false; |
|
|
|
ap.compass_mot = false; |
|
|
|
return MAV_RESULT_TEMPORARILY_REJECTED; |
|
|
|
return MAV_RESULT_TEMPORARILY_REJECTED; |
|
|
|
} |
|
|
|
} |
|
|
@ -98,13 +98,13 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan) |
|
|
|
AP_Notify::flags.esc_calibration = true; |
|
|
|
AP_Notify::flags.esc_calibration = true; |
|
|
|
|
|
|
|
|
|
|
|
// warn user we are starting calibration
|
|
|
|
// warn user we are starting calibration
|
|
|
|
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "Starting calibration"); |
|
|
|
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "Starting calibration"); |
|
|
|
|
|
|
|
|
|
|
|
// inform what type of compensation we are attempting
|
|
|
|
// inform what type of compensation we are attempting
|
|
|
|
if (comp_type == AP_COMPASS_MOT_COMP_CURRENT) { |
|
|
|
if (comp_type == AP_COMPASS_MOT_COMP_CURRENT) { |
|
|
|
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "Current"); |
|
|
|
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "Current"); |
|
|
|
} else{ |
|
|
|
} else{ |
|
|
|
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "Throttle"); |
|
|
|
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "Throttle"); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// disable throttle and battery failsafe
|
|
|
|
// disable throttle and battery failsafe
|
|
|
@ -248,10 +248,10 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan) |
|
|
|
} |
|
|
|
} |
|
|
|
compass.save_motor_compensation(); |
|
|
|
compass.save_motor_compensation(); |
|
|
|
// display success message
|
|
|
|
// display success message
|
|
|
|
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "Calibration successful"); |
|
|
|
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "Calibration successful"); |
|
|
|
} else { |
|
|
|
} else { |
|
|
|
// compensation vector never updated, report failure
|
|
|
|
// compensation vector never updated, report failure
|
|
|
|
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_NOTICE, "Failed"); |
|
|
|
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_NOTICE, "Failed"); |
|
|
|
compass.motor_compensation_type(AP_COMPASS_MOT_COMP_DISABLED); |
|
|
|
compass.motor_compensation_type(AP_COMPASS_MOT_COMP_DISABLED); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|