2015-05-29 23:12:49 -03:00
|
|
|
#include "Copter.h"
|
|
|
|
|
2014-02-07 01:31:34 -04:00
|
|
|
/*
|
|
|
|
compass/motor interference calibration
|
|
|
|
*/
|
|
|
|
|
|
|
|
// setup_compassmot - sets compass's motor interference parameters
|
2019-06-21 20:49:52 -03:00
|
|
|
MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
|
2014-02-07 01:31:34 -04:00
|
|
|
{
|
2015-07-15 03:08:13 -03:00
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
|
|
|
// compassmot not implemented for tradheli
|
2018-02-22 23:11:12 -04:00
|
|
|
return MAV_RESULT_UNSUPPORTED;
|
2015-07-15 03:08:13 -03:00
|
|
|
#else
|
2014-02-07 01:31:34 -04:00
|
|
|
int8_t comp_type; // throttle or current based compensation
|
2014-07-22 04:31:45 -03:00
|
|
|
Vector3f compass_base[COMPASS_MAX_INSTANCES]; // compass vector when throttle is zero
|
|
|
|
Vector3f motor_impact[COMPASS_MAX_INSTANCES]; // impact of motors on compass vector
|
|
|
|
Vector3f motor_impact_scaled[COMPASS_MAX_INSTANCES]; // impact of motors on compass vector scaled with throttle
|
|
|
|
Vector3f motor_compensation[COMPASS_MAX_INSTANCES]; // final compensation to be stored to eeprom
|
2014-02-07 01:31:34 -04:00
|
|
|
float throttle_pct; // throttle as a percentage 0.0 ~ 1.0
|
|
|
|
float throttle_pct_max = 0.0f; // maximum throttle reached (as a percentage 0~1.0)
|
|
|
|
float current_amps_max = 0.0f; // maximum current reached
|
2019-06-02 21:11:57 -03:00
|
|
|
float interference_pct[COMPASS_MAX_INSTANCES]{}; // interference as a percentage of total mag field (for reporting purposes only)
|
2014-02-07 01:31:34 -04:00
|
|
|
uint32_t last_run_time;
|
|
|
|
uint32_t last_send_time;
|
|
|
|
bool updated = false; // have we updated the compensation vector at least once
|
|
|
|
uint8_t command_ack_start = command_ack_counter;
|
|
|
|
|
2014-02-19 00:29:36 -04:00
|
|
|
// exit immediately if we are already in compassmot
|
|
|
|
if (ap.compass_mot) {
|
|
|
|
// ignore restart messages
|
2016-10-01 21:25:53 -03:00
|
|
|
return MAV_RESULT_TEMPORARILY_REJECTED;
|
2018-08-01 23:34:11 -03:00
|
|
|
} else {
|
2014-02-19 00:29:36 -04:00
|
|
|
ap.compass_mot = true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check compass is enabled
|
2021-07-27 21:27:39 -03:00
|
|
|
if (!AP::compass().available()) {
|
2017-02-13 22:14:55 -04:00
|
|
|
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Compass disabled");
|
2014-02-19 00:29:36 -04:00
|
|
|
ap.compass_mot = false;
|
2016-10-01 21:25:53 -03:00
|
|
|
return MAV_RESULT_TEMPORARILY_REJECTED;
|
2014-02-19 00:29:36 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// check compass health
|
|
|
|
compass.read();
|
2014-07-22 04:31:45 -03:00
|
|
|
for (uint8_t i=0; i<compass.get_count(); i++) {
|
|
|
|
if (!compass.healthy(i)) {
|
2017-02-13 22:14:55 -04:00
|
|
|
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Check compass");
|
2014-07-22 04:31:45 -03:00
|
|
|
ap.compass_mot = false;
|
2016-10-01 21:25:53 -03:00
|
|
|
return MAV_RESULT_TEMPORARILY_REJECTED;
|
2014-07-22 04:31:45 -03:00
|
|
|
}
|
2014-02-07 01:31:34 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// check if radio is calibrated
|
2017-08-20 03:24:33 -03:00
|
|
|
if (!arming.rc_calibration_checks(true)) {
|
2017-02-13 22:14:55 -04:00
|
|
|
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "RC not calibrated");
|
2014-02-19 00:29:36 -04:00
|
|
|
ap.compass_mot = false;
|
2016-10-01 21:25:53 -03:00
|
|
|
return MAV_RESULT_TEMPORARILY_REJECTED;
|
2014-02-07 01:31:34 -04:00
|
|
|
}
|
|
|
|
|
2014-02-19 00:29:36 -04:00
|
|
|
// check throttle is at zero
|
|
|
|
read_radio();
|
ArduCopter: Fix up after refactoring RC_Channel class
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
|
|
|
if (channel_throttle->get_control_in() != 0) {
|
2017-02-13 22:14:55 -04:00
|
|
|
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Throttle not zero");
|
2014-02-19 00:29:36 -04:00
|
|
|
ap.compass_mot = false;
|
2016-10-01 21:25:53 -03:00
|
|
|
return MAV_RESULT_TEMPORARILY_REJECTED;
|
2014-02-07 01:31:34 -04:00
|
|
|
}
|
|
|
|
|
2014-02-19 00:29:36 -04:00
|
|
|
// check we are landed
|
|
|
|
if (!ap.land_complete) {
|
2017-02-13 22:14:55 -04:00
|
|
|
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Not landed");
|
2014-02-19 00:29:36 -04:00
|
|
|
ap.compass_mot = false;
|
2016-10-01 21:25:53 -03:00
|
|
|
return MAV_RESULT_TEMPORARILY_REJECTED;
|
2014-02-19 00:29:36 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// disable cpu failsafe
|
|
|
|
failsafe_disable();
|
|
|
|
|
2019-07-07 11:36:07 -03:00
|
|
|
float current;
|
|
|
|
|
2014-02-19 00:29:36 -04:00
|
|
|
// default compensation type to use current if possible
|
2019-07-07 11:36:07 -03:00
|
|
|
if (battery.current_amps(current)) {
|
2014-02-19 00:29:36 -04:00
|
|
|
comp_type = AP_COMPASS_MOT_COMP_CURRENT;
|
2018-08-01 23:34:11 -03:00
|
|
|
} else {
|
2014-02-19 00:29:36 -04:00
|
|
|
comp_type = AP_COMPASS_MOT_COMP_THROTTLE;
|
|
|
|
}
|
|
|
|
|
|
|
|
// send back initial ACK
|
2021-08-18 19:56:15 -03:00
|
|
|
mavlink_msg_command_ack_send(gcs_chan.get_chan(), MAV_CMD_PREFLIGHT_CALIBRATION,0,
|
|
|
|
0, 0, 0, 0);
|
2014-02-19 00:29:36 -04:00
|
|
|
|
|
|
|
// flash leds
|
|
|
|
AP_Notify::flags.esc_calibration = true;
|
2014-02-07 01:31:34 -04:00
|
|
|
|
2014-02-19 00:29:36 -04:00
|
|
|
// warn user we are starting calibration
|
2017-02-13 22:14:55 -04:00
|
|
|
gcs_chan.send_text(MAV_SEVERITY_INFO, "Starting calibration");
|
2014-02-07 01:31:34 -04:00
|
|
|
|
|
|
|
// inform what type of compensation we are attempting
|
2014-02-19 00:29:36 -04:00
|
|
|
if (comp_type == AP_COMPASS_MOT_COMP_CURRENT) {
|
2017-02-13 22:14:55 -04:00
|
|
|
gcs_chan.send_text(MAV_SEVERITY_INFO, "Current");
|
2018-08-01 23:34:11 -03:00
|
|
|
} else {
|
2017-02-13 22:14:55 -04:00
|
|
|
gcs_chan.send_text(MAV_SEVERITY_INFO, "Throttle");
|
2014-02-07 01:31:34 -04:00
|
|
|
}
|
|
|
|
|
2018-02-28 19:32:16 -04:00
|
|
|
// disable throttle failsafe
|
2022-07-05 00:08:57 -03:00
|
|
|
g.failsafe_throttle.set(FS_THR_DISABLED);
|
2014-02-07 01:31:34 -04:00
|
|
|
|
2014-02-19 00:29:36 -04:00
|
|
|
// disable motor compensation
|
|
|
|
compass.motor_compensation_type(AP_COMPASS_MOT_COMP_DISABLED);
|
2014-07-22 04:31:45 -03:00
|
|
|
for (uint8_t i=0; i<compass.get_count(); i++) {
|
|
|
|
compass.set_motor_compensation(i, Vector3f(0,0,0));
|
|
|
|
}
|
2014-02-07 01:31:34 -04:00
|
|
|
|
2014-02-19 00:29:36 -04:00
|
|
|
// get initial compass readings
|
2014-02-07 01:31:34 -04:00
|
|
|
compass.read();
|
|
|
|
|
|
|
|
// store initial x,y,z compass values
|
2014-07-22 04:31:45 -03:00
|
|
|
// initialise interference percentage
|
|
|
|
for (uint8_t i=0; i<compass.get_count(); i++) {
|
2015-09-28 16:57:03 -03:00
|
|
|
compass_base[i] = compass.get_field(i);
|
2014-07-22 04:31:45 -03:00
|
|
|
interference_pct[i] = 0.0f;
|
|
|
|
}
|
2014-02-07 01:31:34 -04:00
|
|
|
|
2019-05-15 01:10:12 -03:00
|
|
|
EXPECT_DELAY_MS(5000);
|
2019-05-06 22:59:14 -03:00
|
|
|
|
2014-02-07 01:31:34 -04:00
|
|
|
// enable motors and pass through throttle
|
2015-04-22 15:59:34 -03:00
|
|
|
enable_motor_output();
|
2017-01-09 03:31:26 -04:00
|
|
|
motors->armed(true);
|
2019-09-11 22:59:25 -03:00
|
|
|
hal.util->set_soft_armed(true);
|
2014-02-07 01:31:34 -04:00
|
|
|
|
|
|
|
// initialise run time
|
|
|
|
last_run_time = millis();
|
|
|
|
last_send_time = millis();
|
|
|
|
|
|
|
|
// main run while there is no user input and the compass is healthy
|
2018-08-01 23:36:52 -03:00
|
|
|
while (command_ack_start == command_ack_counter && compass.healthy() && motors->armed()) {
|
2019-05-15 01:10:12 -03:00
|
|
|
EXPECT_DELAY_MS(5000);
|
2019-05-06 22:59:14 -03:00
|
|
|
|
2014-02-07 01:31:34 -04:00
|
|
|
// 50hz loop
|
2014-02-19 00:29:36 -04:00
|
|
|
if (millis() - last_run_time < 20) {
|
2014-02-07 01:31:34 -04:00
|
|
|
hal.scheduler->delay(5);
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
last_run_time = millis();
|
|
|
|
|
|
|
|
// read radio input
|
|
|
|
read_radio();
|
2018-08-01 23:34:11 -03:00
|
|
|
|
2014-02-07 01:31:34 -04:00
|
|
|
// pass through throttle to motors
|
2017-11-02 23:35:14 -03:00
|
|
|
SRV_Channels::cork();
|
2022-03-11 13:29:59 -04:00
|
|
|
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f);
|
2017-11-02 23:35:14 -03:00
|
|
|
SRV_Channels::push();
|
2018-08-01 23:34:11 -03:00
|
|
|
|
2014-02-07 01:31:34 -04:00
|
|
|
// read some compass values
|
|
|
|
compass.read();
|
2018-08-01 23:34:11 -03:00
|
|
|
|
2014-02-07 01:31:34 -04:00
|
|
|
// read current
|
2018-02-28 19:32:16 -04:00
|
|
|
battery.read();
|
2018-08-01 23:34:11 -03:00
|
|
|
|
2014-02-07 01:31:34 -04:00
|
|
|
// calculate scaling for throttle
|
2022-03-11 13:29:59 -04:00
|
|
|
throttle_pct = (float)channel_throttle->get_control_in() * 0.001f;
|
2014-02-07 01:31:34 -04:00
|
|
|
throttle_pct = constrain_float(throttle_pct,0.0f,1.0f);
|
2014-07-22 04:31:45 -03:00
|
|
|
|
2021-10-15 19:37:03 -03:00
|
|
|
// record maximum throttle
|
|
|
|
throttle_pct_max = MAX(throttle_pct_max, throttle_pct);
|
|
|
|
|
2019-07-07 11:36:07 -03:00
|
|
|
if (!battery.current_amps(current)) {
|
|
|
|
current = 0;
|
|
|
|
}
|
|
|
|
current_amps_max = MAX(current_amps_max, current);
|
|
|
|
|
2014-02-19 00:29:36 -04:00
|
|
|
// if throttle is near zero, update base x,y,z values
|
2022-01-03 19:40:26 -04:00
|
|
|
if (!is_positive(throttle_pct)) {
|
2014-07-22 04:31:45 -03:00
|
|
|
for (uint8_t i=0; i<compass.get_count(); i++) {
|
2015-09-28 16:57:03 -03:00
|
|
|
compass_base[i] = compass_base[i] * 0.99f + compass.get_field(i) * 0.01f;
|
2014-07-22 04:31:45 -03:00
|
|
|
}
|
2014-02-07 01:31:34 -04:00
|
|
|
} else {
|
|
|
|
|
|
|
|
// calculate diff from compass base and scale with throttle
|
2014-07-22 04:31:45 -03:00
|
|
|
for (uint8_t i=0; i<compass.get_count(); i++) {
|
2015-09-28 16:57:03 -03:00
|
|
|
motor_impact[i] = compass.get_field(i) - compass_base[i];
|
2014-07-22 04:31:45 -03:00
|
|
|
}
|
|
|
|
|
2014-02-07 01:31:34 -04:00
|
|
|
// throttle based compensation
|
2014-02-19 00:29:36 -04:00
|
|
|
if (comp_type == AP_COMPASS_MOT_COMP_THROTTLE) {
|
2014-07-22 04:31:45 -03:00
|
|
|
// for each compass
|
|
|
|
for (uint8_t i=0; i<compass.get_count(); i++) {
|
|
|
|
// scale by throttle
|
|
|
|
motor_impact_scaled[i] = motor_impact[i] / throttle_pct;
|
|
|
|
// adjust the motor compensation to negate the impact
|
|
|
|
motor_compensation[i] = motor_compensation[i] * 0.99f - motor_impact_scaled[i] * 0.01f;
|
|
|
|
}
|
2014-02-07 01:31:34 -04:00
|
|
|
updated = true;
|
|
|
|
} else {
|
2014-07-22 04:31:45 -03:00
|
|
|
// for each compass
|
|
|
|
for (uint8_t i=0; i<compass.get_count(); i++) {
|
|
|
|
// adjust the motor compensation to negate the impact if drawing over 3amps
|
2019-07-07 11:36:07 -03:00
|
|
|
if (current >= 3.0f) {
|
|
|
|
motor_impact_scaled[i] = motor_impact[i] / current;
|
2014-07-22 04:31:45 -03:00
|
|
|
motor_compensation[i] = motor_compensation[i] * 0.99f - motor_impact_scaled[i] * 0.01f;
|
|
|
|
updated = true;
|
|
|
|
}
|
2014-02-07 01:31:34 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2014-02-19 00:29:36 -04:00
|
|
|
// calculate interference percentage at full throttle as % of total mag field
|
|
|
|
if (comp_type == AP_COMPASS_MOT_COMP_THROTTLE) {
|
2014-07-22 04:31:45 -03:00
|
|
|
for (uint8_t i=0; i<compass.get_count(); i++) {
|
|
|
|
// interference is impact@fullthrottle / mag field * 100
|
2016-08-17 08:21:05 -03:00
|
|
|
interference_pct[i] = motor_compensation[i].length() / (float)arming.compass_magfield_expected() * 100.0f;
|
2014-07-22 04:31:45 -03:00
|
|
|
}
|
2018-08-01 23:34:11 -03:00
|
|
|
} else {
|
2014-07-22 04:31:45 -03:00
|
|
|
for (uint8_t i=0; i<compass.get_count(); i++) {
|
|
|
|
// interference is impact/amp * (max current seen / max throttle seen) / mag field * 100
|
2016-08-17 08:21:05 -03:00
|
|
|
interference_pct[i] = motor_compensation[i].length() * (current_amps_max/throttle_pct_max) / (float)arming.compass_magfield_expected() * 100.0f;
|
2014-07-22 04:31:45 -03:00
|
|
|
}
|
2014-02-19 00:29:36 -04:00
|
|
|
}
|
2014-02-07 01:31:34 -04:00
|
|
|
}
|
2018-08-01 23:34:11 -03:00
|
|
|
|
2015-11-19 23:04:45 -04:00
|
|
|
if (AP_HAL::millis() - last_send_time > 500) {
|
|
|
|
last_send_time = AP_HAL::millis();
|
2019-06-21 20:49:52 -03:00
|
|
|
mavlink_msg_compassmot_status_send(gcs_chan.get_chan(),
|
ArduCopter: Fix up after refactoring RC_Channel class
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
|
|
|
channel_throttle->get_control_in(),
|
2019-07-07 11:36:07 -03:00
|
|
|
current,
|
2019-11-19 03:10:45 -04:00
|
|
|
interference_pct[0],
|
|
|
|
motor_compensation[0].x,
|
|
|
|
motor_compensation[0].y,
|
|
|
|
motor_compensation[0].z);
|
2021-10-08 08:59:29 -03:00
|
|
|
#if HAL_WITH_ESC_TELEM
|
|
|
|
// send ESC telemetry to monitor ESC and motor temperatures
|
|
|
|
AP::esc_telem().send_esc_telemetry_mavlink(gcs_chan.get_chan());
|
|
|
|
#endif
|
2014-02-07 01:31:34 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// stop motors
|
2017-01-09 03:31:26 -04:00
|
|
|
motors->output_min();
|
|
|
|
motors->armed(false);
|
2019-09-11 22:59:25 -03:00
|
|
|
hal.util->set_soft_armed(false);
|
2014-02-07 01:31:34 -04:00
|
|
|
|
|
|
|
// set and save motor compensation
|
2014-02-19 00:29:36 -04:00
|
|
|
if (updated) {
|
2014-02-07 01:31:34 -04:00
|
|
|
compass.motor_compensation_type(comp_type);
|
2014-07-22 04:31:45 -03:00
|
|
|
for (uint8_t i=0; i<compass.get_count(); i++) {
|
|
|
|
compass.set_motor_compensation(i, motor_compensation[i]);
|
|
|
|
}
|
2014-02-07 01:31:34 -04:00
|
|
|
compass.save_motor_compensation();
|
2014-02-19 00:29:36 -04:00
|
|
|
// display success message
|
2017-02-13 22:14:55 -04:00
|
|
|
gcs_chan.send_text(MAV_SEVERITY_INFO, "Calibration successful");
|
2014-02-07 01:31:34 -04:00
|
|
|
} else {
|
|
|
|
// compensation vector never updated, report failure
|
2017-02-13 22:14:55 -04:00
|
|
|
gcs_chan.send_text(MAV_SEVERITY_NOTICE, "Failed");
|
2014-02-07 01:31:34 -04:00
|
|
|
compass.motor_compensation_type(AP_COMPASS_MOT_COMP_DISABLED);
|
|
|
|
}
|
|
|
|
|
2014-02-19 00:29:36 -04:00
|
|
|
// turn off notify leds
|
|
|
|
AP_Notify::flags.esc_calibration = false;
|
|
|
|
|
|
|
|
// re-enable cpu failsafe
|
|
|
|
failsafe_enable();
|
|
|
|
|
|
|
|
// re-enable failsafes
|
|
|
|
g.failsafe_throttle.load();
|
|
|
|
|
|
|
|
// flag we have completed
|
|
|
|
ap.compass_mot = false;
|
|
|
|
|
2016-10-01 21:25:53 -03:00
|
|
|
return MAV_RESULT_ACCEPTED;
|
2015-07-15 03:08:13 -03:00
|
|
|
#endif // FRAME_CONFIG != HELI_FRAME
|
2014-02-07 01:31:34 -04:00
|
|
|
}
|