Copter: pass GCS_MAVLink object rather than channel number in motortest

This commit is contained in:
Peter Barker 2019-06-25 12:09:15 +10:00 committed by Andrew Tridgell
parent 84eff51539
commit bb3d2a0b37
3 changed files with 6 additions and 8 deletions

View File

@ -771,8 +771,8 @@ private:
// motor_test.cpp
void motor_test_output();
bool mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc);
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);
bool mavlink_motor_test_check(const GCS_MAVLINK &gcs_chan, bool check_rc);
MAV_RESULT mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, uint8_t motor_seq, uint8_t throttle_type, uint16_t throttle_value, float timeout_sec, uint8_t motor_count);
void motor_test_stop();
// motors.cpp

View File

@ -711,7 +711,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
// param4 : timeout (in seconds)
// param5 : num_motors (in sequence)
// param6 : compass learning (0: disabled, 1: enabled)
return copter.mavlink_motor_test_start(chan,
return copter.mavlink_motor_test_start(*this,
(uint8_t)packet.param1,
(uint8_t)packet.param2,
(uint16_t)packet.param3,

View File

@ -94,10 +94,8 @@ void Copter::motor_test_output()
// mavlink_motor_test_check - perform checks before motor tests can begin
// return true if tests can continue, false if not
bool Copter::mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc)
bool Copter::mavlink_motor_test_check(const GCS_MAVLINK &gcs_chan, bool check_rc)
{
GCS_MAVLINK_Copter &gcs_chan = gcs().chan(chan-MAVLINK_COMM_0);
// check board has initialised
if (!ap.initialised) {
gcs_chan.send_text(MAV_SEVERITY_CRITICAL,"Motor Test: Board initialising");
@ -128,7 +126,7 @@ bool Copter::mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc)
// mavlink_motor_test_start - start motor test - spin a single motor at a specified pwm
// returns MAV_RESULT_ACCEPTED on success, MAV_RESULT_FAILED on failure
MAV_RESULT Copter::mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type, uint16_t throttle_value,
MAV_RESULT Copter::mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, uint8_t motor_seq, uint8_t throttle_type, uint16_t throttle_value,
float timeout_sec, uint8_t motor_count)
{
if (motor_count == 0) {
@ -142,7 +140,7 @@ MAV_RESULT Copter::mavlink_motor_test_start(mavlink_channel_t chan, uint8_t moto
The RC calibrated check can be skipped if direct pwm is
supplied
*/
if (!mavlink_motor_test_check(chan, throttle_type != 1)) {
if (!mavlink_motor_test_check(gcs_chan, throttle_type != 1)) {
return MAV_RESULT_FAILED;
} else {
// start test