mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 11:06:04 +08:00
mavlink remove clang warning/error
This commit is contained in:
committed by
Lorenz Meier
parent
1ecdb0f6fb
commit
464e2f14c1
@@ -1109,7 +1109,7 @@ void
|
|||||||
MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg)
|
MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg)
|
||||||
{
|
{
|
||||||
/* telemetry status supported only on first ORB_MULTI_MAX_INSTANCES mavlink channels */
|
/* telemetry status supported only on first ORB_MULTI_MAX_INSTANCES mavlink channels */
|
||||||
if (_mavlink->get_channel() < ORB_MULTI_MAX_INSTANCES) {
|
if (_mavlink->get_channel() < (mavlink_channel_t)ORB_MULTI_MAX_INSTANCES) {
|
||||||
mavlink_radio_status_t rstatus;
|
mavlink_radio_status_t rstatus;
|
||||||
mavlink_msg_radio_status_decode(msg, &rstatus);
|
mavlink_msg_radio_status_decode(msg, &rstatus);
|
||||||
|
|
||||||
@@ -1319,7 +1319,7 @@ void
|
|||||||
MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg)
|
MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg)
|
||||||
{
|
{
|
||||||
/* telemetry status supported only on first TELEMETRY_STATUS_ORB_ID_NUM mavlink channels */
|
/* telemetry status supported only on first TELEMETRY_STATUS_ORB_ID_NUM mavlink channels */
|
||||||
if (_mavlink->get_channel() < ORB_MULTI_MAX_INSTANCES) {
|
if (_mavlink->get_channel() < (mavlink_channel_t)ORB_MULTI_MAX_INSTANCES) {
|
||||||
mavlink_heartbeat_t hb;
|
mavlink_heartbeat_t hb;
|
||||||
mavlink_msg_heartbeat_decode(msg, &hb);
|
mavlink_msg_heartbeat_decode(msg, &hb);
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user