Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduCopter/compassmot.cpp
Views: 1798
#include "Copter.h"12/*3compass/motor interference calibration4*/56// setup_compassmot - sets compass's motor interference parameters7MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)8{9#if FRAME_CONFIG == HELI_FRAME10// compassmot not implemented for tradheli11return MAV_RESULT_UNSUPPORTED;12#else13int8_t comp_type; // throttle or current based compensation14Vector3f compass_base[COMPASS_MAX_INSTANCES]; // compass vector when throttle is zero15Vector3f motor_impact[COMPASS_MAX_INSTANCES]; // impact of motors on compass vector16Vector3f motor_impact_scaled[COMPASS_MAX_INSTANCES]; // impact of motors on compass vector scaled with throttle17Vector3f motor_compensation[COMPASS_MAX_INSTANCES]; // final compensation to be stored to eeprom18float throttle_pct; // throttle as a percentage 0.0 ~ 1.019float throttle_pct_max = 0.0f; // maximum throttle reached (as a percentage 0~1.0)20float current_amps_max = 0.0f; // maximum current reached21float interference_pct[COMPASS_MAX_INSTANCES]{}; // interference as a percentage of total mag field (for reporting purposes only)22uint32_t last_run_time;23uint32_t last_send_time;24bool updated = false; // have we updated the compensation vector at least once25uint8_t command_ack_start = command_ack_counter;2627// exit immediately if we are already in compassmot28if (ap.compass_mot) {29// ignore restart messages30return MAV_RESULT_TEMPORARILY_REJECTED;31} else {32ap.compass_mot = true;33}3435// check compass is enabled36if (!AP::compass().available()) {37gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Compass disabled");38ap.compass_mot = false;39return MAV_RESULT_TEMPORARILY_REJECTED;40}4142// check compass health43compass.read();44for (uint8_t i=0; i<compass.get_count(); i++) {45if (!compass.healthy(i)) {46gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Check compass");47ap.compass_mot = false;48return MAV_RESULT_TEMPORARILY_REJECTED;49}50}5152// check if radio is calibrated53if (!arming.rc_calibration_checks(true)) {54gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "RC not calibrated");55ap.compass_mot = false;56return MAV_RESULT_TEMPORARILY_REJECTED;57}5859// check throttle is at zero60read_radio();61if (channel_throttle->get_control_in() != 0) {62gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Throttle not zero");63ap.compass_mot = false;64return MAV_RESULT_TEMPORARILY_REJECTED;65}6667// check we are landed68if (!ap.land_complete) {69gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Not landed");70ap.compass_mot = false;71return MAV_RESULT_TEMPORARILY_REJECTED;72}7374// disable cpu failsafe75failsafe_disable();7677float current;7879// default compensation type to use current if possible80if (battery.current_amps(current)) {81comp_type = AP_COMPASS_MOT_COMP_CURRENT;82} else {83comp_type = AP_COMPASS_MOT_COMP_THROTTLE;84}8586// send back initial ACK87mavlink_msg_command_ack_send(gcs_chan.get_chan(), MAV_CMD_PREFLIGHT_CALIBRATION,0,880, 0, 0, 0);8990// flash leds91AP_Notify::flags.esc_calibration = true;9293// warn user we are starting calibration94gcs_chan.send_text(MAV_SEVERITY_INFO, "Starting calibration");9596// inform what type of compensation we are attempting97if (comp_type == AP_COMPASS_MOT_COMP_CURRENT) {98gcs_chan.send_text(MAV_SEVERITY_INFO, "Current");99} else {100gcs_chan.send_text(MAV_SEVERITY_INFO, "Throttle");101}102103// disable throttle failsafe104g.failsafe_throttle.set(FS_THR_DISABLED);105106// disable motor compensation107compass.motor_compensation_type(AP_COMPASS_MOT_COMP_DISABLED);108for (uint8_t i=0; i<compass.get_count(); i++) {109compass.set_motor_compensation(i, Vector3f(0,0,0));110}111112// get initial compass readings113compass.read();114115// store initial x,y,z compass values116// initialise interference percentage117for (uint8_t i=0; i<compass.get_count(); i++) {118compass_base[i] = compass.get_field(i);119interference_pct[i] = 0.0f;120}121122EXPECT_DELAY_MS(5000);123124// enable motors and pass through throttle125motors->output_min(); // output lowest possible value to motors126motors->armed(true);127hal.util->set_soft_armed(true);128129// initialise run time130last_run_time = millis();131last_send_time = millis();132133// main run while there is no user input and the compass is healthy134while (command_ack_start == command_ack_counter && compass.healthy() && motors->armed()) {135EXPECT_DELAY_MS(5000);136137// 50hz loop138if (millis() - last_run_time < 20) {139hal.scheduler->delay(5);140continue;141}142last_run_time = millis();143144// read radio input145read_radio();146147// pass through throttle to motors148auto &srv = AP::srv();149srv.cork();150motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f);151srv.push();152153// read some compass values154compass.read();155156// read current157battery.read();158159// calculate scaling for throttle160throttle_pct = (float)channel_throttle->get_control_in() * 0.001f;161throttle_pct = constrain_float(throttle_pct,0.0f,1.0f);162163// record maximum throttle164throttle_pct_max = MAX(throttle_pct_max, throttle_pct);165166if (!battery.current_amps(current)) {167current = 0;168}169current_amps_max = MAX(current_amps_max, current);170171// if throttle is near zero, update base x,y,z values172if (!is_positive(throttle_pct)) {173for (uint8_t i=0; i<compass.get_count(); i++) {174compass_base[i] = compass_base[i] * 0.99f + compass.get_field(i) * 0.01f;175}176} else {177178// calculate diff from compass base and scale with throttle179for (uint8_t i=0; i<compass.get_count(); i++) {180motor_impact[i] = compass.get_field(i) - compass_base[i];181}182183// throttle based compensation184if (comp_type == AP_COMPASS_MOT_COMP_THROTTLE) {185// for each compass186for (uint8_t i=0; i<compass.get_count(); i++) {187// scale by throttle188motor_impact_scaled[i] = motor_impact[i] / throttle_pct;189// adjust the motor compensation to negate the impact190motor_compensation[i] = motor_compensation[i] * 0.99f - motor_impact_scaled[i] * 0.01f;191}192updated = true;193} else {194// for each compass195for (uint8_t i=0; i<compass.get_count(); i++) {196// adjust the motor compensation to negate the impact if drawing over 3amps197if (current >= 3.0f) {198motor_impact_scaled[i] = motor_impact[i] / current;199motor_compensation[i] = motor_compensation[i] * 0.99f - motor_impact_scaled[i] * 0.01f;200updated = true;201}202}203}204205// calculate interference percentage at full throttle as % of total mag field206if (comp_type == AP_COMPASS_MOT_COMP_THROTTLE) {207for (uint8_t i=0; i<compass.get_count(); i++) {208// interference is impact@fullthrottle / mag field * 100209interference_pct[i] = motor_compensation[i].length() / (float)arming.compass_magfield_expected() * 100.0f;210}211} else {212for (uint8_t i=0; i<compass.get_count(); i++) {213// interference is impact/amp * (max current seen / max throttle seen) / mag field * 100214interference_pct[i] = motor_compensation[i].length() * (current_amps_max/throttle_pct_max) / (float)arming.compass_magfield_expected() * 100.0f;215}216}217}218219if (AP_HAL::millis() - last_send_time > 500) {220last_send_time = AP_HAL::millis();221mavlink_msg_compassmot_status_send(gcs_chan.get_chan(),222channel_throttle->get_control_in(),223current,224interference_pct[0],225motor_compensation[0].x,226motor_compensation[0].y,227motor_compensation[0].z);228#if HAL_WITH_ESC_TELEM229// send ESC telemetry to monitor ESC and motor temperatures230AP::esc_telem().send_esc_telemetry_mavlink(gcs_chan.get_chan());231#endif232#if CONFIG_HAL_BOARD == HAL_BOARD_SITL233// a lot of autotest timeouts are based on receiving system time234gcs_chan.send_system_time();235// autotesting of compassmot wants to see RC channels message236gcs_chan.send_rc_channels();237#endif238}239}240241// stop motors242motors->output_min();243motors->armed(false);244hal.util->set_soft_armed(false);245246// set and save motor compensation247if (updated) {248compass.motor_compensation_type(comp_type);249for (uint8_t i=0; i<compass.get_count(); i++) {250compass.set_motor_compensation(i, motor_compensation[i]);251}252compass.save_motor_compensation();253// display success message254gcs_chan.send_text(MAV_SEVERITY_INFO, "Calibration successful");255} else {256// compensation vector never updated, report failure257gcs_chan.send_text(MAV_SEVERITY_NOTICE, "Failed");258compass.motor_compensation_type(AP_COMPASS_MOT_COMP_DISABLED);259}260261// turn off notify leds262AP_Notify::flags.esc_calibration = false;263264// re-enable cpu failsafe265failsafe_enable();266267// re-enable failsafes268g.failsafe_throttle.load();269270// flag we have completed271ap.compass_mot = false;272273return MAV_RESULT_ACCEPTED;274#endif // FRAME_CONFIG != HELI_FRAME275}276277278