20 #define AP_ACCELCAL_POSITION_REQUEST_INTERVAL_MS 1000 39 uint8_t num_active_calibrators = 0;
41 num_active_calibrators++;
76 case ACCELCAL_VEHICLE_POS_LEVEL:
79 case ACCELCAL_VEHICLE_POS_LEFT:
80 msg =
"on its LEFT side";
82 case ACCELCAL_VEHICLE_POS_RIGHT:
83 msg =
"on its RIGHT side";
85 case ACCELCAL_VEHICLE_POS_NOSEDOWN:
88 case ACCELCAL_VEHICLE_POS_NOSEUP:
91 case ACCELCAL_VEHICLE_POS_BACK:
98 _printf(
"Place vehicle %s and press any key.", msg);
206 _printf(
"Calibration successful");
219 _printf(
"Calibration cancelled");
269 _printf(
"Not ready to sample");
362 if (msg->msgid == MAVLINK_MSG_ID_COMMAND_ACK) {
389 if (msg[strlen(msg)-1] ==
'\n') {
391 msg[strlen(msg)-1] = 0;
398 while (uart->
txspace() < MAVLINK_NUM_NON_PAYLOAD_BYTES+MAVLINK_MSG_ID_STATUSTEXT_LEN) {
402 #if !APM_BUILD_TYPE(APM_BUILD_Replay)
void _printf(const char *,...)
MAVLink transport control class.
Interface definition for the various Ground Control System.
void start(enum accel_cal_fit_type_t fit_type=ACCEL_CAL_AXIS_ALIGNED_ELLIPSOID, uint8_t num_samples=6, float sample_time=0.5f)
virtual uint32_t txspace()=0
accel_cal_status_t _status
static uint8_t _num_clients
static void register_client(AP_AccelCal_Client *client)
uint8_t get_num_samples_collected() const
virtual void delay(uint16_t ms)=0
AP_HAL::UARTDriver * get_uart()
int vsnprintf(char *str, size_t size, const char *format, va_list ap)
#define AP_ACCELCAL_POSITION_REQUEST_INTERVAL_MS
virtual void _acal_event_success()
void handleMessage(const mavlink_message_t *msg)
#define AP_ACCELCAL_MAX_NUM_CLIENTS
void send_text(MAV_SEVERITY severity, const char *fmt,...)
bool gcs_vehicle_position(float position)
virtual AccelCalibrator * _acal_get_calibrator(uint8_t instance)=0
static bool _start_collect_sample
virtual void _acal_save_calibrations()=0
enum accel_cal_status_t get_status() const
bool _waiting_for_mavlink_ack
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
AccelCalibrator * get_calibrator(uint8_t i)
virtual void _acal_event_failure()
uint8_t _num_active_calibrators
static AP_AccelCal_Client * _clients[AP_ACCELCAL_MAX_NUM_CLIENTS]
virtual void _acal_event_cancellation()
bool client_active(uint8_t client_num)
void send_accelcal_vehicle_position(uint32_t position)
void start(GCS_MAVLINK *gcs)
uint32_t _last_position_request_ms
AP_HAL::Scheduler * scheduler
accel_cal_status_t _last_result