Path: blob/master/libraries/AP_AccelCal/AP_AccelCal.cpp
9378 views
/*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, uint8_t sysid, uint8_t compid)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_sysid = sysid;204_compid = compid;205_use_gcs_snoop = true;206_last_position_request_ms = 0;207_step = 0;208209_last_result = ACCEL_CAL_NOT_STARTED;210211update_status();212}213214void AP_AccelCal::success()215{216_printf("Calibration successful");217218for(uint8_t i=0 ; i < _num_clients ; i++) {219_clients[i]->_acal_event_success();220}221222_last_result = ACCEL_CAL_SUCCESS;223224clear();225}226227void AP_AccelCal::cancel()228{229_printf("Calibration cancelled");230231for(uint8_t i=0 ; i < _num_clients ; i++) {232_clients[i]->_acal_event_cancellation();233}234235_last_result = ACCEL_CAL_NOT_STARTED;236237clear();238}239240void AP_AccelCal::fail()241{242_printf("Calibration FAILED");243244for(uint8_t i=0 ; i < _num_clients ; i++) {245_clients[i]->_acal_event_failure();246}247248_last_result = ACCEL_CAL_FAILED;249250clear();251}252253void AP_AccelCal::clear()254{255if (!_started) {256return;257}258259AccelCalibrator *cal;260for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {261cal->clear();262}263264_step = 0;265_started = false;266_saving = false;267268update_status();269}270271void AP_AccelCal::collect_sample()272{273if (_status != ACCEL_CAL_WAITING_FOR_ORIENTATION) {274return;275}276277for(uint8_t i=0; i<_num_clients; i++) {278if (client_active(i) && !_clients[i]->_acal_get_ready_to_sample()) {279_printf("Not ready to sample");280return;281}282}283284AccelCalibrator *cal;285for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {286cal->collect_sample();287}288_start_collect_sample = false;289update_status();290}291292void AP_AccelCal::register_client(AP_AccelCal_Client* client) {293if (client == nullptr || _num_clients >= AP_ACCELCAL_MAX_NUM_CLIENTS) {294return;295}296297298for(uint8_t i=0; i<_num_clients; i++) {299if(_clients[i] == client) {300return;301}302}303_clients[_num_clients] = client;304_num_clients++;305}306307AccelCalibrator* AP_AccelCal::get_calibrator(uint8_t index) {308AccelCalibrator* ret;309for(uint8_t i=0; i<_num_clients; i++) {310for(uint8_t j=0 ; (ret = _clients[i]->_acal_get_calibrator(j)) ; j++) {311if (index == 0) {312return ret;313}314index--;315}316}317return nullptr;318}319320void AP_AccelCal::update_status() {321AccelCalibrator *cal;322323if (!get_calibrator(0)) {324// no calibrators325_status = ACCEL_CAL_NOT_STARTED;326return;327}328329for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {330if (cal->get_status() == ACCEL_CAL_FAILED) {331_status = ACCEL_CAL_FAILED; //fail if even one of the calibration has332return;333}334}335336for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {337if (cal->get_status() == ACCEL_CAL_COLLECTING_SAMPLE) {338_status = ACCEL_CAL_COLLECTING_SAMPLE; // move to Collecting sample state if all the callibrators have339return;340}341}342343for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {344if (cal->get_status() == ACCEL_CAL_WAITING_FOR_ORIENTATION) {345_status = ACCEL_CAL_WAITING_FOR_ORIENTATION; // move to waiting for user ack for orientation confirmation346return;347}348}349350for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {351if (cal->get_status() == ACCEL_CAL_NOT_STARTED) {352_status = ACCEL_CAL_NOT_STARTED; // we haven't started if all the calibrators haven't353return;354}355}356357_status = ACCEL_CAL_SUCCESS; // we have succeeded calibration if all the calibrators have358}359360bool AP_AccelCal::client_active(uint8_t client_num)361{362return (bool)_clients[client_num]->_acal_get_calibrator(0);363}364365#if HAL_GCS_ENABLED366void AP_AccelCal::handle_command_ack(const mavlink_command_ack_t &packet, uint8_t src_sysid, uint8_t src_compid)367{368if(_sysid != src_sysid || _compid != src_compid) {369return;370}371372if (!_waiting_for_mavlink_ack) {373return;374}375// this is support for the old, non-accelcal-specific calibration.376// The GCS is expected to send back a COMMAND_ACK when the vehicle377// is posed, but we placed no constraints on the result code or378// the command field in the ack packet. That meant that any ACK379// would move the cal process forward - and since we don't even380// check the source system/component here the process could easily381// fail due to other ACKs floating around the mavlink network.382// GCSs should be moved to using the non-gcs-snoop method. As a383// round-up:384// MAVProxy: command=1-6 depending on pose, result=1385// QGC: command=0, result=1386// MissionPlanner: uses new ACCELCAL_VEHICLE_POS387if (packet.command > 6) {388// not an acknowledgement for a vehicle position389return;390}391if (packet.result != MAV_RESULT_TEMPORARILY_REJECTED) {392// not an acknowledgement for a vehicle position393return;394}395_waiting_for_mavlink_ack = false;396_start_collect_sample = true;397}398399bool AP_AccelCal::gcs_vehicle_position(float position)400{401_use_gcs_snoop = false;402403if (_status == ACCEL_CAL_WAITING_FOR_ORIENTATION && is_equal((float) _step, position)) {404_start_collect_sample = true;405return true;406}407408return false;409}410#endif411412// true if we are in a calibration process413bool AP_AccelCal::running(void) const414{415return _status == ACCEL_CAL_WAITING_FOR_ORIENTATION || _status == ACCEL_CAL_COLLECTING_SAMPLE;416}417#endif //HAL_INS_ACCELCAL_ENABLED418419420