Rover: tighten return types of mavlink functions and variables

This commit is contained in:
Peter Barker 2017-11-27 17:19:58 +11:00 committed by Francisco Ferreira
parent 3f7eb69327
commit 1d2ec9054b
3 changed files with 4 additions and 4 deletions

View File

@ -655,7 +655,7 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
// decode packet // decode packet
mavlink_command_int_t packet; mavlink_command_int_t packet;
mavlink_msg_command_int_decode(msg, &packet); mavlink_msg_command_int_decode(msg, &packet);
uint8_t result = MAV_RESULT_UNSUPPORTED; MAV_RESULT result = MAV_RESULT_UNSUPPORTED;
switch (packet.command) { switch (packet.command) {
@ -749,7 +749,7 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
mavlink_command_long_t packet; mavlink_command_long_t packet;
mavlink_msg_command_long_decode(msg, &packet); mavlink_msg_command_long_decode(msg, &packet);
uint8_t result = MAV_RESULT_UNSUPPORTED; MAV_RESULT result = MAV_RESULT_UNSUPPORTED;
// do command // do command

View File

@ -587,7 +587,7 @@ public:
// Motor test // Motor test
void motor_test_output(); void motor_test_output();
bool mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc, uint8_t motor_seq, uint8_t throttle_type, int16_t throttle_value); bool mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc, uint8_t motor_seq, uint8_t throttle_type, int16_t throttle_value);
uint8_t mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type, int16_t throttle_value, float timeout_sec); MAV_RESULT mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type, int16_t throttle_value, float timeout_sec);
void motor_test_stop(); void motor_test_stop();
}; };

View File

@ -110,7 +110,7 @@ bool Rover::mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc, uint
// mavlink_motor_test_start - start motor test - spin a single motor at a specified pwm // 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 // returns MAV_RESULT_ACCEPTED on success, MAV_RESULT_FAILED on failure
uint8_t Rover::mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type, int16_t throttle_value, float timeout_sec) MAV_RESULT Rover::mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type, int16_t throttle_value, float timeout_sec)
{ {
// if test has not started try to start it // if test has not started try to start it
if (!motor_test) { if (!motor_test) {