mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: keep a bitmap of what mavlink channels are active
- this will allow for looping over active channels in libraries - expose active channel mask
This commit is contained in:
parent
1d42eda4da
commit
3020d91dcd
|
@ -195,6 +195,10 @@ public:
|
||||||
void send_sensor_offsets(const AP_InertialSensor &ins, const Compass &compass, AP_Baro &barometer);
|
void send_sensor_offsets(const AP_InertialSensor &ins, const Compass &compass, AP_Baro &barometer);
|
||||||
void send_ahrs(AP_AHRS &ahrs);
|
void send_ahrs(AP_AHRS &ahrs);
|
||||||
|
|
||||||
|
// return a bitmap of active channels. Used by libraries to loop
|
||||||
|
// over active channels to send to all active channels
|
||||||
|
static uint8_t active_channel_mask(void) { return mavlink_active; }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
void handleMessage(mavlink_message_t * msg);
|
void handleMessage(mavlink_message_t * msg);
|
||||||
|
|
||||||
|
@ -293,7 +297,8 @@ private:
|
||||||
uint8_t next_deferred_message;
|
uint8_t next_deferred_message;
|
||||||
uint8_t num_deferred_messages;
|
uint8_t num_deferred_messages;
|
||||||
|
|
||||||
static bool mavlink_active;
|
// bitmask of what mavlink channels are active
|
||||||
|
static uint8_t mavlink_active;
|
||||||
|
|
||||||
// vehicle specific message send function
|
// vehicle specific message send function
|
||||||
bool try_send_message(enum ap_message id);
|
bool try_send_message(enum ap_message id);
|
||||||
|
|
|
@ -23,7 +23,7 @@
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
uint32_t GCS_MAVLINK::last_radio_status_remrssi_ms;
|
uint32_t GCS_MAVLINK::last_radio_status_remrssi_ms;
|
||||||
bool GCS_MAVLINK::mavlink_active = false;
|
uint8_t GCS_MAVLINK::mavlink_active = 0;
|
||||||
|
|
||||||
GCS_MAVLINK::GCS_MAVLINK() :
|
GCS_MAVLINK::GCS_MAVLINK() :
|
||||||
waypoint_receive_timeout(5000)
|
waypoint_receive_timeout(5000)
|
||||||
|
@ -871,7 +871,7 @@ GCS_MAVLINK::update(void (*run_cli)(AP_HAL::UARTDriver *))
|
||||||
if (run_cli != NULL) {
|
if (run_cli != NULL) {
|
||||||
/* allow CLI to be started by hitting enter 3 times, if no
|
/* allow CLI to be started by hitting enter 3 times, if no
|
||||||
* heartbeat packets have been received */
|
* heartbeat packets have been received */
|
||||||
if (!mavlink_active && (hal.scheduler->millis() - _cli_timeout) < 20000 &&
|
if ((mavlink_active==0) && (hal.scheduler->millis() - _cli_timeout) < 20000 &&
|
||||||
comm_is_idle(chan)) {
|
comm_is_idle(chan)) {
|
||||||
if (c == '\n' || c == '\r') {
|
if (c == '\n' || c == '\r') {
|
||||||
crlf_count++;
|
crlf_count++;
|
||||||
|
@ -889,7 +889,7 @@ GCS_MAVLINK::update(void (*run_cli)(AP_HAL::UARTDriver *))
|
||||||
// we exclude radio packets to make it possible to use the
|
// we exclude radio packets to make it possible to use the
|
||||||
// CLI over the radio
|
// CLI over the radio
|
||||||
if (msg.msgid != MAVLINK_MSG_ID_RADIO && msg.msgid != MAVLINK_MSG_ID_RADIO_STATUS) {
|
if (msg.msgid != MAVLINK_MSG_ID_RADIO && msg.msgid != MAVLINK_MSG_ID_RADIO_STATUS) {
|
||||||
mavlink_active = true;
|
mavlink_active |= (1U<<chan);
|
||||||
}
|
}
|
||||||
handleMessage(&msg);
|
handleMessage(&msg);
|
||||||
}
|
}
|
||||||
|
|
|
@ -2298,9 +2298,8 @@
|
||||||
<description>Request for terrain data and terrain status</description>
|
<description>Request for terrain data and terrain status</description>
|
||||||
<field type="uint32_t" name="lat">Latitude of SW corner of first grid (degrees *10^7)</field>
|
<field type="uint32_t" name="lat">Latitude of SW corner of first grid (degrees *10^7)</field>
|
||||||
<field type="uint32_t" name="lon">Longitude of SW corner of first grid (in degrees *10^7)</field>
|
<field type="uint32_t" name="lon">Longitude of SW corner of first grid (in degrees *10^7)</field>
|
||||||
<field type="uint16_t" name="mask">Bitmask of requested 5x5 grids (row major 4x4 array of grids)</field>
|
|
||||||
<field type="uint16_t" name="grid_spacing">Grid spacing in meters</field>
|
<field type="uint16_t" name="grid_spacing">Grid spacing in meters</field>
|
||||||
<field type="uint16_t" name="flags">Terrain status flags</field>
|
<field type="uint8_t[9]" name="mask">Bitmask of requested 5x5 grids (row major 9x9 array of grids)</field>
|
||||||
</message>
|
</message>
|
||||||
<message id="134" name="TERRAIN_DATA">
|
<message id="134" name="TERRAIN_DATA">
|
||||||
<description>Terrain data sent from GCS</description>
|
<description>Terrain data sent from GCS</description>
|
||||||
|
|
Loading…
Reference in New Issue