AP_Compass: make handle_mag_cal_command return type stricter
This commit is contained in:
parent
2b6752e0b4
commit
6b53b5b5f3
@ -122,7 +122,7 @@ public:
|
|||||||
/*
|
/*
|
||||||
handle an incoming MAG_CAL command
|
handle an incoming MAG_CAL command
|
||||||
*/
|
*/
|
||||||
uint8_t handle_mag_cal_command(const mavlink_command_long_t &packet);
|
MAV_RESULT handle_mag_cal_command(const mavlink_command_long_t &packet);
|
||||||
|
|
||||||
void send_mag_cal_progress(mavlink_channel_t chan);
|
void send_mag_cal_progress(mavlink_channel_t chan);
|
||||||
void send_mag_cal_report(mavlink_channel_t chan);
|
void send_mag_cal_report(mavlink_channel_t chan);
|
||||||
|
@ -267,9 +267,9 @@ Compass::_get_cal_mask() const
|
|||||||
/*
|
/*
|
||||||
handle an incoming MAG_CAL command
|
handle an incoming MAG_CAL command
|
||||||
*/
|
*/
|
||||||
uint8_t Compass::handle_mag_cal_command(const mavlink_command_long_t &packet)
|
MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_long_t &packet)
|
||||||
{
|
{
|
||||||
uint8_t result = MAV_RESULT_FAILED;
|
MAV_RESULT result = MAV_RESULT_FAILED;
|
||||||
|
|
||||||
switch (packet.command) {
|
switch (packet.command) {
|
||||||
case MAV_CMD_DO_START_MAG_CAL: {
|
case MAV_CMD_DO_START_MAG_CAL: {
|
||||||
|
Loading…
Reference in New Issue
Block a user