GCS_MAVLink: remove unused send_gimbal_report
This commit is contained in:
parent
a714384e1c
commit
3ac5ad8e33
@ -298,7 +298,6 @@ public:
|
|||||||
void send_vibration() const;
|
void send_vibration() const;
|
||||||
void send_mount_status() const;
|
void send_mount_status() const;
|
||||||
void send_named_float(const char *name, float value) const;
|
void send_named_float(const char *name, float value) const;
|
||||||
void send_gimbal_report() const;
|
|
||||||
void send_home_position() const;
|
void send_home_position() const;
|
||||||
void send_gps_global_origin() const;
|
void send_gps_global_origin() const;
|
||||||
virtual void send_attitude_target() {};
|
virtual void send_attitude_target() {};
|
||||||
|
@ -892,7 +892,6 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
|
|||||||
{ MAVLINK_MSG_ID_CAMERA_FEEDBACK, MSG_CAMERA_FEEDBACK},
|
{ MAVLINK_MSG_ID_CAMERA_FEEDBACK, MSG_CAMERA_FEEDBACK},
|
||||||
{ MAVLINK_MSG_ID_MOUNT_STATUS, MSG_MOUNT_STATUS},
|
{ MAVLINK_MSG_ID_MOUNT_STATUS, MSG_MOUNT_STATUS},
|
||||||
{ MAVLINK_MSG_ID_OPTICAL_FLOW, MSG_OPTICAL_FLOW},
|
{ MAVLINK_MSG_ID_OPTICAL_FLOW, MSG_OPTICAL_FLOW},
|
||||||
{ MAVLINK_MSG_ID_GIMBAL_REPORT, MSG_GIMBAL_REPORT},
|
|
||||||
{ MAVLINK_MSG_ID_MAG_CAL_PROGRESS, MSG_MAG_CAL_PROGRESS},
|
{ MAVLINK_MSG_ID_MAG_CAL_PROGRESS, MSG_MAG_CAL_PROGRESS},
|
||||||
{ MAVLINK_MSG_ID_MAG_CAL_REPORT, MSG_MAG_CAL_REPORT},
|
{ MAVLINK_MSG_ID_MAG_CAL_REPORT, MSG_MAG_CAL_REPORT},
|
||||||
{ MAVLINK_MSG_ID_EKF_STATUS_REPORT, MSG_EKF_STATUS_REPORT},
|
{ MAVLINK_MSG_ID_EKF_STATUS_REPORT, MSG_EKF_STATUS_REPORT},
|
||||||
@ -5040,17 +5039,6 @@ void GCS_MAVLINK::send_global_position_int()
|
|||||||
ahrs.yaw_sensor); // compass heading in 1/100 degree
|
ahrs.yaw_sensor); // compass heading in 1/100 degree
|
||||||
}
|
}
|
||||||
|
|
||||||
void GCS_MAVLINK::send_gimbal_report() const
|
|
||||||
{
|
|
||||||
#if HAL_MOUNT_ENABLED
|
|
||||||
AP_Mount *mount = AP::mount();
|
|
||||||
if (mount == nullptr) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
mount->send_gimbal_report(chan);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
void GCS_MAVLINK::send_mount_status() const
|
void GCS_MAVLINK::send_mount_status() const
|
||||||
{
|
{
|
||||||
#if HAL_MOUNT_ENABLED
|
#if HAL_MOUNT_ENABLED
|
||||||
@ -5201,11 +5189,6 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
|||||||
queued_param_send();
|
queued_param_send();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_GIMBAL_REPORT:
|
|
||||||
CHECK_PAYLOAD_SIZE(GIMBAL_REPORT);
|
|
||||||
send_gimbal_report();
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MSG_HEARTBEAT:
|
case MSG_HEARTBEAT:
|
||||||
CHECK_PAYLOAD_SIZE(HEARTBEAT);
|
CHECK_PAYLOAD_SIZE(HEARTBEAT);
|
||||||
last_heartbeat_time = AP_HAL::millis();
|
last_heartbeat_time = AP_HAL::millis();
|
||||||
|
@ -51,7 +51,6 @@ enum ap_message : uint8_t {
|
|||||||
MSG_CAMERA_FEEDBACK,
|
MSG_CAMERA_FEEDBACK,
|
||||||
MSG_MOUNT_STATUS,
|
MSG_MOUNT_STATUS,
|
||||||
MSG_OPTICAL_FLOW,
|
MSG_OPTICAL_FLOW,
|
||||||
MSG_GIMBAL_REPORT,
|
|
||||||
MSG_MAG_CAL_PROGRESS,
|
MSG_MAG_CAL_PROGRESS,
|
||||||
MSG_MAG_CAL_REPORT,
|
MSG_MAG_CAL_REPORT,
|
||||||
MSG_EKF_STATUS_REPORT,
|
MSG_EKF_STATUS_REPORT,
|
||||||
|
Loading…
Reference in New Issue
Block a user