Tracker: rename gcs[] to gcs_chan[]
Wish to use gcs() to return the gcs singleton
This commit is contained in:
parent
45e0765b97
commit
14470573f6
@ -58,7 +58,7 @@ void Tracker::send_heartbeat(mavlink_channel_t chan)
|
||||
base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
|
||||
}
|
||||
|
||||
gcs[chan-MAVLINK_COMM_0].send_heartbeat(MAV_TYPE_ANTENNA_TRACKER,
|
||||
gcs_chan[chan-MAVLINK_COMM_0].send_heartbeat(MAV_TYPE_ANTENNA_TRACKER,
|
||||
base_mode,
|
||||
custom_mode,
|
||||
system_status);
|
||||
@ -111,7 +111,7 @@ void Tracker::send_hwstatus(mavlink_channel_t chan)
|
||||
|
||||
void Tracker::send_waypoint_request(mavlink_channel_t chan)
|
||||
{
|
||||
gcs[chan-MAVLINK_COMM_0].queued_waypoint_send();
|
||||
gcs_chan[chan-MAVLINK_COMM_0].queued_waypoint_send();
|
||||
}
|
||||
|
||||
void Tracker::send_nav_controller_output(mavlink_channel_t chan)
|
||||
@ -486,7 +486,7 @@ void Tracker::mavlink_check_target(const mavlink_message_t* msg)
|
||||
// send data stream request to target on all channels
|
||||
// Note: this doesn't check success for all sends meaning it's not guaranteed the vehicle's positions will be sent at 1hz
|
||||
for (uint8_t i=0; i < num_gcs; i++) {
|
||||
if (gcs[i].initialised) {
|
||||
if (gcs_chan[i].initialised) {
|
||||
// request position
|
||||
if (HAVE_PAYLOAD_SPACE((mavlink_channel_t)i, DATA_STREAM)) {
|
||||
mavlink_msg_request_data_stream_send(
|
||||
@ -889,7 +889,7 @@ mission_failed:
|
||||
void Tracker::mavlink_delay_cb()
|
||||
{
|
||||
static uint32_t last_1hz, last_50hz, last_5s;
|
||||
if (!gcs[0].initialised) return;
|
||||
if (!gcs_chan[0].initialised) return;
|
||||
|
||||
tracker.in_mavlink_delay = true;
|
||||
|
||||
@ -918,8 +918,8 @@ void Tracker::mavlink_delay_cb()
|
||||
void Tracker::gcs_send_message(enum ap_message id)
|
||||
{
|
||||
for (uint8_t i=0; i<num_gcs; i++) {
|
||||
if (gcs[i].initialised) {
|
||||
gcs[i].send_message(id);
|
||||
if (gcs_chan[i].initialised) {
|
||||
gcs_chan[i].send_message(id);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -930,8 +930,8 @@ void Tracker::gcs_send_message(enum ap_message id)
|
||||
void Tracker::gcs_data_stream_send(void)
|
||||
{
|
||||
for (uint8_t i=0; i<num_gcs; i++) {
|
||||
if (gcs[i].initialised) {
|
||||
gcs[i].data_stream_send();
|
||||
if (gcs_chan[i].initialised) {
|
||||
gcs_chan[i].data_stream_send();
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -942,8 +942,8 @@ void Tracker::gcs_data_stream_send(void)
|
||||
void Tracker::gcs_update(void)
|
||||
{
|
||||
for (uint8_t i=0; i<num_gcs; i++) {
|
||||
if (gcs[i].initialised) {
|
||||
gcs[i].update(nullptr);
|
||||
if (gcs_chan[i].initialised) {
|
||||
gcs_chan[i].update(nullptr);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -107,7 +107,7 @@ void Tracker::log_init(void)
|
||||
DataFlash.Prep();
|
||||
gcs_send_text(MAV_SEVERITY_INFO, "Prepared log system");
|
||||
for (uint8_t i=0; i<num_gcs; i++) {
|
||||
gcs[i].reset_cli_timeout();
|
||||
gcs_chan[i].reset_cli_timeout();
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -253,19 +253,19 @@ const AP_Param::Info Tracker::var_info[] = {
|
||||
|
||||
// @Group: SR0_
|
||||
// @Path: GCS_Mavlink.cpp
|
||||
GOBJECTN(gcs[0], gcs0, "SR0_", GCS_MAVLINK),
|
||||
GOBJECTN(gcs_chan[0], gcs0, "SR0_", GCS_MAVLINK),
|
||||
|
||||
// @Group: SR1_
|
||||
// @Path: GCS_Mavlink.cpp
|
||||
GOBJECTN(gcs[1], gcs1, "SR1_", GCS_MAVLINK),
|
||||
GOBJECTN(gcs_chan[1], gcs1, "SR1_", GCS_MAVLINK),
|
||||
|
||||
// @Group: SR2_
|
||||
// @Path: GCS_Mavlink.cpp
|
||||
GOBJECTN(gcs[2], gcs2, "SR2_", GCS_MAVLINK),
|
||||
GOBJECTN(gcs_chan[2], gcs2, "SR2_", GCS_MAVLINK),
|
||||
|
||||
// @Group: SR3_
|
||||
// @Path: GCS_Mavlink.cpp
|
||||
GOBJECTN(gcs[3], gcs3, "SR3_", GCS_MAVLINK),
|
||||
GOBJECTN(gcs_chan[3], gcs3, "SR3_", GCS_MAVLINK),
|
||||
|
||||
// @Param: LOG_BITMASK
|
||||
// @DisplayName: Log bitmask
|
||||
|
@ -139,7 +139,7 @@ private:
|
||||
|
||||
AP_SerialManager serial_manager;
|
||||
const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS;
|
||||
GCS_MAVLINK_Tracker gcs[MAVLINK_COMM_NUM_BUFFERS];
|
||||
GCS_MAVLINK_Tracker gcs_chan[MAVLINK_COMM_NUM_BUFFERS];
|
||||
|
||||
AP_BoardConfig BoardConfig;
|
||||
|
||||
|
@ -34,7 +34,7 @@ void Tracker::init_tracker()
|
||||
serial_manager.init();
|
||||
|
||||
// setup first port early to allow BoardConfig to report errors
|
||||
gcs[0].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0);
|
||||
gcs_chan[0].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0);
|
||||
|
||||
// Register mavlink_delay_cb, which will run anytime you have
|
||||
// more than 5ms remaining in your call to hal.scheduler->delay
|
||||
@ -58,8 +58,8 @@ void Tracker::init_tracker()
|
||||
|
||||
// setup telem slots with serial ports
|
||||
for (uint8_t i = 1; i < MAVLINK_COMM_NUM_BUFFERS; i++) {
|
||||
gcs[i].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, i);
|
||||
gcs[i].set_snoop(mavlink_snoop_static);
|
||||
gcs_chan[i].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, i);
|
||||
gcs_chan[i].set_snoop(mavlink_snoop_static);
|
||||
}
|
||||
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user