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/libraries/AP_AccelCal/AP_AccelCal.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.5This program is distributed in the hope that it will be useful,6but WITHOUT ANY WARRANTY; without even the implied warranty of7MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the8GNU General Public License for more details.9You should have received a copy of the GNU General Public License10along with this program. If not, see <http://www.gnu.org/licenses/>.11*/1213#include "AP_AccelCal.h"1415#if HAL_INS_ACCELCAL_ENABLED1617#include <stdarg.h>18#include <AP_HAL/AP_HAL.h>19#include <GCS_MAVLink/GCS.h>2021#define AP_ACCELCAL_POSITION_REQUEST_INTERVAL_MS 10002223#define _printf(fmt, args ...) do { \24if (_gcs != nullptr) { \25_gcs->send_text(MAV_SEVERITY_CRITICAL, fmt, ## args); \26} \27} while (0)282930const extern AP_HAL::HAL& hal;31static bool _start_collect_sample;3233uint8_t AP_AccelCal::_num_clients = 0;34AP_AccelCal_Client* AP_AccelCal::_clients[AP_ACCELCAL_MAX_NUM_CLIENTS] {};3536void AP_AccelCal::update()37{38if (!get_calibrator(0)) {39// no calibrators40return;41}4243if (_started) {44update_status();4546uint8_t num_active_calibrators = 0;47for(uint8_t i=0; get_calibrator(i) != nullptr; i++) {48num_active_calibrators++;49}50if (num_active_calibrators != _num_active_calibrators) {51fail();52return;53}54if(_start_collect_sample) {55collect_sample();56}57AccelCalibrator *cal;58switch(_status) {59case ACCEL_CAL_NOT_STARTED:60fail();61return;62case ACCEL_CAL_WAITING_FOR_ORIENTATION: {63// if we're waiting for orientation, first ensure that all calibrators are on the same step64uint8_t step;65if ((cal = get_calibrator(0)) == nullptr) {66fail();67return;68}69step = cal->get_num_samples_collected()+1;7071for(uint8_t i=1 ; (cal = get_calibrator(i)) ; i++) {72if (step != cal->get_num_samples_collected()+1) {73fail();74return;75}76}77// if we're on a new step, print a message describing the step78if (step != _step) {79_step = step;8081if(_use_gcs_snoop) {82const char *msg;83switch (step) {84case ACCELCAL_VEHICLE_POS_LEVEL:85msg = "level";86break;87case ACCELCAL_VEHICLE_POS_LEFT:88msg = "on its LEFT side";89break;90case ACCELCAL_VEHICLE_POS_RIGHT:91msg = "on its RIGHT side";92break;93case ACCELCAL_VEHICLE_POS_NOSEDOWN:94msg = "nose DOWN";95break;96case ACCELCAL_VEHICLE_POS_NOSEUP:97msg = "nose UP";98break;99case ACCELCAL_VEHICLE_POS_BACK:100msg = "on its BACK";101break;102default:103fail();104return;105}106_printf("Place vehicle %s and press any key.", msg);107_waiting_for_mavlink_ack = true;108}109}110111uint32_t now = AP_HAL::millis();112if (now - _last_position_request_ms > AP_ACCELCAL_POSITION_REQUEST_INTERVAL_MS) {113_last_position_request_ms = now;114_gcs->send_accelcal_vehicle_position(step);115}116break;117}118case ACCEL_CAL_COLLECTING_SAMPLE:119// check for timeout120121for(uint8_t i=0; (cal = get_calibrator(i)); i++) {122cal->check_for_timeout();123}124125update_status();126127if (_status == ACCEL_CAL_FAILED) {128fail();129}130return;131case ACCEL_CAL_SUCCESS:132// save133if (_saving) {134bool done = true;135for(uint8_t i=0; i<_num_clients; i++) {136if (client_active(i) && _clients[i]->_acal_get_saving()) {137done = false;138break;139}140}141if (done) {142success();143}144return;145} else {146for(uint8_t i=0; i<_num_clients; i++) {147if(client_active(i) && _clients[i]->_acal_get_fail()) {148fail();149return;150}151}152for(uint8_t i=0; i<_num_clients; i++) {153if(client_active(i)) {154_clients[i]->_acal_save_calibrations();155}156}157_saving = true;158}159return;160default:161case ACCEL_CAL_FAILED:162fail();163return;164}165} else if (_last_result != ACCEL_CAL_NOT_STARTED) {166// only continuously report if we have ever completed a calibration167uint32_t now = AP_HAL::millis();168if (now - _last_position_request_ms > AP_ACCELCAL_POSITION_REQUEST_INTERVAL_MS) {169_last_position_request_ms = now;170switch (_last_result) {171case ACCEL_CAL_SUCCESS:172_gcs->send_accelcal_vehicle_position(ACCELCAL_VEHICLE_POS_SUCCESS);173break;174case ACCEL_CAL_FAILED:175_gcs->send_accelcal_vehicle_position(ACCELCAL_VEHICLE_POS_FAILED);176break;177default:178// should never hit this state179break;180}181}182}183}184185void AP_AccelCal::start(GCS_MAVLINK *gcs)186{187if (gcs == nullptr || _started) {188return;189}190_start_collect_sample = false;191_num_active_calibrators = 0;192193AccelCalibrator *cal;194for(uint8_t i=0; (cal = get_calibrator(i)); i++) {195cal->clear();196cal->start(ACCEL_CAL_AXIS_ALIGNED_ELLIPSOID, 6, 0.5f);197_num_active_calibrators++;198}199200_started = true;201_saving = false;202_gcs = gcs;203_use_gcs_snoop = true;204_last_position_request_ms = 0;205_step = 0;206207_last_result = ACCEL_CAL_NOT_STARTED;208209update_status();210}211212void AP_AccelCal::success()213{214_printf("Calibration successful");215216for(uint8_t i=0 ; i < _num_clients ; i++) {217_clients[i]->_acal_event_success();218}219220_last_result = ACCEL_CAL_SUCCESS;221222clear();223}224225void AP_AccelCal::cancel()226{227_printf("Calibration cancelled");228229for(uint8_t i=0 ; i < _num_clients ; i++) {230_clients[i]->_acal_event_cancellation();231}232233_last_result = ACCEL_CAL_NOT_STARTED;234235clear();236}237238void AP_AccelCal::fail()239{240_printf("Calibration FAILED");241242for(uint8_t i=0 ; i < _num_clients ; i++) {243_clients[i]->_acal_event_failure();244}245246_last_result = ACCEL_CAL_FAILED;247248clear();249}250251void AP_AccelCal::clear()252{253if (!_started) {254return;255}256257AccelCalibrator *cal;258for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {259cal->clear();260}261262_step = 0;263_started = false;264_saving = false;265266update_status();267}268269void AP_AccelCal::collect_sample()270{271if (_status != ACCEL_CAL_WAITING_FOR_ORIENTATION) {272return;273}274275for(uint8_t i=0; i<_num_clients; i++) {276if (client_active(i) && !_clients[i]->_acal_get_ready_to_sample()) {277_printf("Not ready to sample");278return;279}280}281282AccelCalibrator *cal;283for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {284cal->collect_sample();285}286_start_collect_sample = false;287update_status();288}289290void AP_AccelCal::register_client(AP_AccelCal_Client* client) {291if (client == nullptr || _num_clients >= AP_ACCELCAL_MAX_NUM_CLIENTS) {292return;293}294295296for(uint8_t i=0; i<_num_clients; i++) {297if(_clients[i] == client) {298return;299}300}301_clients[_num_clients] = client;302_num_clients++;303}304305AccelCalibrator* AP_AccelCal::get_calibrator(uint8_t index) {306AccelCalibrator* ret;307for(uint8_t i=0; i<_num_clients; i++) {308for(uint8_t j=0 ; (ret = _clients[i]->_acal_get_calibrator(j)) ; j++) {309if (index == 0) {310return ret;311}312index--;313}314}315return nullptr;316}317318void AP_AccelCal::update_status() {319AccelCalibrator *cal;320321if (!get_calibrator(0)) {322// no calibrators323_status = ACCEL_CAL_NOT_STARTED;324return;325}326327for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {328if (cal->get_status() == ACCEL_CAL_FAILED) {329_status = ACCEL_CAL_FAILED; //fail if even one of the calibration has330return;331}332}333334for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {335if (cal->get_status() == ACCEL_CAL_COLLECTING_SAMPLE) {336_status = ACCEL_CAL_COLLECTING_SAMPLE; // move to Collecting sample state if all the callibrators have337return;338}339}340341for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {342if (cal->get_status() == ACCEL_CAL_WAITING_FOR_ORIENTATION) {343_status = ACCEL_CAL_WAITING_FOR_ORIENTATION; // move to waiting for user ack for orientation confirmation344return;345}346}347348for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {349if (cal->get_status() == ACCEL_CAL_NOT_STARTED) {350_status = ACCEL_CAL_NOT_STARTED; // we haven't started if all the calibrators haven't351return;352}353}354355_status = ACCEL_CAL_SUCCESS; // we have succeeded calibration if all the calibrators have356return;357}358359bool AP_AccelCal::client_active(uint8_t client_num)360{361return (bool)_clients[client_num]->_acal_get_calibrator(0);362}363364#if HAL_GCS_ENABLED365void AP_AccelCal::handle_command_ack(const mavlink_command_ack_t &packet)366{367if (!_waiting_for_mavlink_ack) {368return;369}370// this is support for the old, non-accelcal-specific calibration.371// The GCS is expected to send back a COMMAND_ACK when the vehicle372// is posed, but we placed no constraints on the result code or373// the command field in the ack packet. That meant that any ACK374// would move the cal process forward - and since we don't even375// check the source system/component here the process could easily376// fail due to other ACKs floating around the mavlink network.377// GCSs should be moved to using the non-gcs-snoop method. As a378// round-up:379// MAVProxy: command=1-6 depending on pose, result=1380// QGC: command=0, result=1381// MissionPlanner: uses new ACCELCAL_VEHICLE_POS382if (packet.command > 6) {383// not an acknowledgement for a vehicle position384return;385}386if (packet.result != MAV_RESULT_TEMPORARILY_REJECTED) {387// not an acknowledgement for a vehicle position388return;389}390_waiting_for_mavlink_ack = false;391_start_collect_sample = true;392}393394bool AP_AccelCal::gcs_vehicle_position(float position)395{396_use_gcs_snoop = false;397398if (_status == ACCEL_CAL_WAITING_FOR_ORIENTATION && is_equal((float) _step, position)) {399_start_collect_sample = true;400return true;401}402403return false;404}405#endif406407// true if we are in a calibration process408bool AP_AccelCal::running(void) const409{410return _status == ACCEL_CAL_WAITING_FOR_ORIENTATION || _status == ACCEL_CAL_COLLECTING_SAMPLE;411}412#endif //HAL_INS_ACCELCAL_ENABLED413414415