APM:Copter
motor_test.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 /*
4  mavlink motor test - implements the MAV_CMD_DO_MOTOR_TEST mavlink command so that the GCS/pilot can test an individual motor or flaps
5  to ensure proper wiring, rotation.
6  */
7 
8 // motor test definitions
9 #define MOTOR_TEST_PWM_MIN 800 // min pwm value accepted by the test
10 #define MOTOR_TEST_PWM_MAX 2200 // max pwm value accepted by the test
11 #define MOTOR_TEST_TIMEOUT_MS_MAX 30000 // max timeout is 30 seconds
12 
13 static uint32_t motor_test_start_ms; // system time the motor test began
14 static uint32_t motor_test_timeout_ms; // test will timeout this many milliseconds after the motor_test_start_ms
15 static uint8_t motor_test_seq; // motor sequence number of motor being tested
16 static uint8_t motor_test_count; // number of motors to test
17 static uint8_t motor_test_throttle_type; // motor throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through)
18 static uint16_t motor_test_throttle_value; // throttle to be sent to motor, value depends upon it's type
19 
20 // motor_test_output - checks for timeout and sends updates to motors objects
22 {
23  // exit immediately if the motor test is not running
24  if (!ap.motor_test) {
25  return;
26  }
27 
28  // check for test timeout
29  uint32_t now = AP_HAL::millis();
31  if (motor_test_count > 1) {
33  // output zero for 50% of the test time
34  motors->output_min();
35  } else {
36  // move onto next motor
39  motor_test_start_ms = now;
40  if (!motors->armed()) {
41  motors->armed(true);
42  }
43  }
44  return;
45  }
46  // stop motor test
48  } else {
49  int16_t pwm = 0; // pwm that will be output to the motors
50 
51  // calculate pwm based on throttle type
52  switch (motor_test_throttle_type) {
53 
54  case MOTOR_TEST_COMPASS_CAL:
58 
59  case MOTOR_TEST_THROTTLE_PERCENT:
60  // sanity check motor_test_throttle value
61 #if FRAME_CONFIG != HELI_FRAME
62  if (motor_test_throttle_value <= 100) {
63  int16_t pwm_min = motors->get_pwm_output_min();
64  int16_t pwm_max = motors->get_pwm_output_max();
65  pwm = pwm_min + (pwm_max - pwm_min) * (float)motor_test_throttle_value/100.0f;
66  }
67 #endif
68  break;
69 
70  case MOTOR_TEST_THROTTLE_PWM:
72  break;
73 
74  case MOTOR_TEST_THROTTLE_PILOT:
76  break;
77 
78  default:
80  return;
81  }
82 
83  // sanity check throttle values
84  if (pwm >= MOTOR_TEST_PWM_MIN && pwm <= MOTOR_TEST_PWM_MAX ) {
85  // turn on motor to specified pwm vlaue
86  motors->output_test(motor_test_seq, pwm);
87  } else {
89  }
90  }
91 }
92 
93 // mavlink_motor_test_check - perform checks before motor tests can begin
94 // return true if tests can continue, false if not
95 bool Copter::mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc)
96 {
97  GCS_MAVLINK_Copter &gcs_chan = gcs().chan(chan-MAVLINK_COMM_0);
98 
99  // check board has initialised
100  if (!ap.initialised) {
101  gcs_chan.send_text(MAV_SEVERITY_CRITICAL,"Motor Test: Board initialising");
102  return false;
103  }
104 
105  // check rc has been calibrated
106  if (check_rc && !arming.rc_calibration_checks(true)) {
107  gcs_chan.send_text(MAV_SEVERITY_CRITICAL,"Motor Test: RC not calibrated");
108  return false;
109  }
110 
111  // ensure we are landed
112  if (!ap.land_complete) {
113  gcs_chan.send_text(MAV_SEVERITY_CRITICAL,"Motor Test: vehicle not landed");
114  return false;
115  }
116 
117  // check if safety switch has been pushed
119  gcs_chan.send_text(MAV_SEVERITY_CRITICAL,"Motor Test: Safety switch");
120  return false;
121  }
122 
123  // if we got this far the check was successful and the motor test can continue
124  return true;
125 }
126 
127 // mavlink_motor_test_start - start motor test - spin a single motor at a specified pwm
128 // returns MAV_RESULT_ACCEPTED on success, MAV_RESULT_FAILED on failure
129 MAV_RESULT Copter::mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type, uint16_t throttle_value,
130  float timeout_sec, uint8_t motor_count)
131 {
132  if (motor_count == 0) {
133  motor_count = 1;
134  }
135  // if test has not started try to start it
136  if (!ap.motor_test) {
137  gcs().send_text(MAV_SEVERITY_INFO, "starting motor test");
138 
139  /* perform checks that it is ok to start test
140  The RC calibrated check can be skipped if direct pwm is
141  supplied
142  */
143  if (!mavlink_motor_test_check(chan, throttle_type != 1)) {
144  return MAV_RESULT_FAILED;
145  } else {
146  // start test
147  ap.motor_test = true;
148 
149  // enable and arm motors
150  if (!motors->armed()) {
151  init_rc_out();
153  motors->armed(true);
154  }
155 
156  // disable throttle and gps failsafe
159  g.fs_ekf_action = 0;
160 
161  // turn on notify leds
163  }
164  }
165 
166  // set timeout
168  motor_test_timeout_ms = MIN(timeout_sec * 1000, MOTOR_TEST_TIMEOUT_MS_MAX);
169 
170  // store required output
171  motor_test_seq = motor_seq;
172  motor_test_count = motor_count;
173  motor_test_throttle_type = throttle_type;
174  motor_test_throttle_value = throttle_value;
175 
176  if (motor_test_throttle_type == MOTOR_TEST_COMPASS_CAL) {
178  }
179 
180  // return success
181  return MAV_RESULT_ACCEPTED;
182 }
183 
184 // motor_test_stop - stops the motor test
186 {
187  // exit immediately if the test is not running
188  if (!ap.motor_test) {
189  return;
190  }
191 
192  gcs().send_text(MAV_SEVERITY_INFO, "finished motor test");
193 
194  // flag test is complete
195  ap.motor_test = false;
196 
197  // disarm motors
198  motors->armed(false);
199 
200  // reset timeout
203 
204  // re-enable failsafes
205  g.failsafe_throttle.load();
206  g.failsafe_gcs.load();
207  g.fs_ekf_action.load();
208 
209  if (motor_test_throttle_type == MOTOR_TEST_COMPASS_CAL) {
211  }
212 
213  // turn off notify leds
215 }
void per_motor_calibration_end(void)
AP_Arming_Copter arming
Definition: Copter.h:280
static uint16_t motor_test_throttle_value
Definition: motor_test.cpp:18
#define FALLTHROUGH
int16_t get_radio_in() const
MAV_RESULT mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type, uint16_t throttle_value, float timeout_sec, uint8_t motor_count)
Definition: motor_test.cpp:129
bool mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc)
Definition: motor_test.cpp:95
void init_rc_out()
Definition: radio.cpp:52
GCS_Copter & gcs()
Definition: Copter.h:301
static uint8_t motor_test_count
Definition: motor_test.cpp:16
AP_HAL::Util * util
void per_motor_calibration_update(void)
bool rc_calibration_checks(bool display_failure) override
Definition: AP_Arming.cpp:349
MOTOR_CLASS * motors
Definition: Copter.h:422
#define MIN(a, b)
#define FS_GCS_DISABLED
Definition: defines.h:463
#define MOTOR_TEST_PWM_MIN
Definition: motor_test.cpp:9
AP_Int8 failsafe_gcs
Definition: Parameters.h:398
static uint32_t motor_test_start_ms
Definition: motor_test.cpp:13
RC_Channel * channel_throttle
Definition: Copter.h:223
void motor_test_output()
Definition: motor_test.cpp:21
AP_BattMonitor battery
Definition: Copter.h:445
const AP_HAL::HAL & hal
Definition: Copter.cpp:21
#define FS_THR_DISABLED
Definition: defines.h:455
uint32_t millis()
virtual enum safety_state safety_switch_state(void)
GCS_MAVLINK_Copter & chan(const uint8_t ofs) override
Definition: GCS_Copter.h:16
void send_text(MAV_SEVERITY severity, const char *fmt,...)
#define MOTOR_TEST_PWM_MAX
Definition: motor_test.cpp:10
void set_voltage(float voltage)
Parameters g
Definition: Copter.h:208
Compass compass
Definition: Copter.h:235
void per_motor_calibration_start(void)
static struct notify_flags_and_values_type flags
static uint8_t motor_test_throttle_type
Definition: motor_test.cpp:17
AP_Int8 fs_ekf_action
Definition: Parameters.h:453
void motor_test_stop()
Definition: motor_test.cpp:185
AP_Int8 failsafe_throttle
Definition: Parameters.h:421
#define MOTOR_TEST_TIMEOUT_MS_MAX
Definition: motor_test.cpp:11
static uint8_t motor_test_seq
Definition: motor_test.cpp:15
float voltage(uint8_t instance) const
void enable_motor_output()
Definition: radio.cpp:88
static uint32_t motor_test_timeout_ms
Definition: motor_test.cpp:14