mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
GCS_MAVLink: wibble to mavlink_helpers.h to fix build.
This commit is contained in:
parent
2a72c7e730
commit
fd89bacbc8
@ -9,15 +9,6 @@
|
||||
#define MAVLINK_HELPER
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Reset the status of a channel
|
||||
*/
|
||||
MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan);
|
||||
{
|
||||
mavlink_status_t *status = mavlink_get_channel_status(chan);
|
||||
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
|
||||
}
|
||||
|
||||
/*
|
||||
* Internal function to give access to the channel status for each channel
|
||||
*/
|
||||
@ -27,6 +18,15 @@ MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
|
||||
return &m_mavlink_status[chan];
|
||||
}
|
||||
|
||||
/**
|
||||
* Reset the status of a channel
|
||||
*/
|
||||
MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan)
|
||||
{
|
||||
mavlink_status_t *status = mavlink_get_channel_status(chan);
|
||||
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
|
||||
}
|
||||
|
||||
/*
|
||||
* Internal function to give access to the channel buffer for each channel
|
||||
*/
|
||||
|
Loading…
Reference in New Issue
Block a user