GCS_MAVLink: move sending of camera_feedback up
This commit is contained in:
parent
8692bb4619
commit
d1a9128118
@ -293,6 +293,7 @@ protected:
|
|||||||
// message sending functions:
|
// message sending functions:
|
||||||
bool try_send_compass_message(enum ap_message id);
|
bool try_send_compass_message(enum ap_message id);
|
||||||
bool try_send_mission_message(enum ap_message id);
|
bool try_send_mission_message(enum ap_message id);
|
||||||
|
bool try_send_camera_message(enum ap_message id);
|
||||||
void send_hwstatus();
|
void send_hwstatus();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
@ -2113,6 +2113,27 @@ void GCS_MAVLINK::send_hwstatus()
|
|||||||
0);
|
0);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool GCS_MAVLINK::try_send_camera_message(const enum ap_message id)
|
||||||
|
{
|
||||||
|
AP_Camera *camera = get_camera();
|
||||||
|
if (camera == nullptr) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool ret = true;
|
||||||
|
switch(id) {
|
||||||
|
case MSG_CAMERA_FEEDBACK:
|
||||||
|
CHECK_PAYLOAD_SIZE(CAMERA_FEEDBACK);
|
||||||
|
camera->send_feedback(chan);
|
||||||
|
ret = true;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
ret = true;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||||
{
|
{
|
||||||
if (telemetry_delayed()) {
|
if (telemetry_delayed()) {
|
||||||
@ -2155,6 +2176,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
|||||||
ret = true;
|
ret = true;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSG_CAMERA_FEEDBACK:
|
||||||
|
ret = try_send_camera_message(id);
|
||||||
|
break;
|
||||||
|
|
||||||
|
|
||||||
default:
|
default:
|
||||||
// try_send_message must always at some stage return true for
|
// try_send_message must always at some stage return true for
|
||||||
// a message, or we will attempt to infinitely retry the
|
// a message, or we will attempt to infinitely retry the
|
||||||
|
Loading…
Reference in New Issue
Block a user