AP_Mount: remove unimplemented send_gimbal_report
This commit is contained in:
parent
03a2859e0e
commit
5651d8761d
@ -734,16 +734,6 @@ void AP_Mount::handle_param_value(const mavlink_message_t &msg)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// send a GIMBAL_REPORT message to the GCS
|
|
||||||
void AP_Mount::send_gimbal_report(mavlink_channel_t chan)
|
|
||||||
{
|
|
||||||
for (uint8_t instance=0; instance<AP_MOUNT_MAX_INSTANCES; instance++) {
|
|
||||||
if (_backends[instance] != nullptr) {
|
|
||||||
_backends[instance]->send_gimbal_report(chan);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
// singleton instance
|
// singleton instance
|
||||||
AP_Mount *AP_Mount::_singleton;
|
AP_Mount *AP_Mount::_singleton;
|
||||||
|
@ -132,9 +132,6 @@ public:
|
|||||||
void handle_param_value(const mavlink_message_t &msg);
|
void handle_param_value(const mavlink_message_t &msg);
|
||||||
void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg);
|
void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg);
|
||||||
|
|
||||||
// send a GIMBAL_REPORT message to GCS
|
|
||||||
void send_gimbal_report(mavlink_channel_t chan);
|
|
||||||
|
|
||||||
// send a MOUNT_STATUS message to GCS:
|
// send a MOUNT_STATUS message to GCS:
|
||||||
void send_mount_status(mavlink_channel_t chan);
|
void send_mount_status(mavlink_channel_t chan);
|
||||||
|
|
||||||
|
@ -79,9 +79,6 @@ public:
|
|||||||
// handle a PARAM_VALUE message
|
// handle a PARAM_VALUE message
|
||||||
virtual void handle_param_value(const mavlink_message_t &msg) {}
|
virtual void handle_param_value(const mavlink_message_t &msg) {}
|
||||||
|
|
||||||
// send a GIMBAL_REPORT message to the GCS
|
|
||||||
virtual void send_gimbal_report(const mavlink_channel_t chan) {}
|
|
||||||
|
|
||||||
// handle a GLOBAL_POSITION_INT message
|
// handle a GLOBAL_POSITION_INT message
|
||||||
bool handle_global_position_int(uint8_t msg_sysid, const mavlink_global_position_int_t &packet);
|
bool handle_global_position_int(uint8_t msg_sysid, const mavlink_global_position_int_t &packet);
|
||||||
|
|
||||||
|
@ -159,11 +159,4 @@ void AP_Mount_SoloGimbal::handle_gimbal_torque_report(mavlink_channel_t chan, co
|
|||||||
_gimbal.disable_torque_report();
|
_gimbal.disable_torque_report();
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
|
||||||
send a GIMBAL_REPORT message to the GCS
|
|
||||||
*/
|
|
||||||
void AP_Mount_SoloGimbal::send_gimbal_report(mavlink_channel_t chan)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif // HAL_SOLO_GIMBAL_ENABLED
|
#endif // HAL_SOLO_GIMBAL_ENABLED
|
||||||
|
@ -43,9 +43,6 @@ public:
|
|||||||
void handle_gimbal_torque_report(mavlink_channel_t chan, const mavlink_message_t &msg);
|
void handle_gimbal_torque_report(mavlink_channel_t chan, const mavlink_message_t &msg);
|
||||||
void handle_param_value(const mavlink_message_t &msg) override;
|
void handle_param_value(const mavlink_message_t &msg) override;
|
||||||
|
|
||||||
// send a GIMBAL_REPORT message to the GCS
|
|
||||||
void send_gimbal_report(mavlink_channel_t chan) override;
|
|
||||||
|
|
||||||
void update_fast() override;
|
void update_fast() override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
Loading…
Reference in New Issue
Block a user