Plane: tighten handleMessage result type
This commit is contained in:
parent
e39e8359b6
commit
af007c5f0f
@ -906,7 +906,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
|||||||
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) {
|
||||||
|
|
||||||
@ -1037,7 +1037,7 @@ void GCS_MAVLINK_Plane::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
|
||||||
|
|
||||||
|
@ -74,7 +74,7 @@ void QuadPlane::motor_test_output()
|
|||||||
|
|
||||||
// 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 QuadPlane::mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type,
|
MAV_RESULT QuadPlane::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)
|
uint16_t throttle_value, float timeout_sec, uint8_t motor_count)
|
||||||
{
|
{
|
||||||
if (motors->armed()) {
|
if (motors->armed()) {
|
||||||
|
@ -466,9 +466,9 @@ private:
|
|||||||
|
|
||||||
public:
|
public:
|
||||||
void motor_test_output();
|
void motor_test_output();
|
||||||
uint8_t mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type,
|
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,
|
uint16_t throttle_value, float timeout_sec,
|
||||||
uint8_t motor_count);
|
uint8_t motor_count);
|
||||||
private:
|
private:
|
||||||
void motor_test_stop();
|
void motor_test_stop();
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user