mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: tighten return types of mavlink functions and variables
This commit is contained in:
parent
af007c5f0f
commit
398d07a68a
@ -1021,7 +1021,7 @@ private:
|
||||
void update_notify();
|
||||
void motor_test_output();
|
||||
bool mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc);
|
||||
uint8_t 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);
|
||||
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);
|
||||
void motor_test_stop();
|
||||
void arm_motors_check();
|
||||
void auto_disarm_check();
|
||||
|
@ -720,7 +720,7 @@ void GCS_MAVLINK_Copter::send_banner()
|
||||
|
||||
void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
||||
{
|
||||
uint8_t result = MAV_RESULT_FAILED; // assume failure. Each messages id is responsible for return ACK or NAK if required
|
||||
MAV_RESULT result = MAV_RESULT_FAILED; // assume failure. Each messages id is responsible for return ACK or NAK if required
|
||||
|
||||
switch (msg->msgid) {
|
||||
|
||||
|
@ -121,7 +121,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
|
||||
uint8_t 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(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type, uint16_t throttle_value,
|
||||
float timeout_sec, uint8_t motor_count)
|
||||
{
|
||||
if (motor_count == 0) {
|
||||
|
Loading…
Reference in New Issue
Block a user