mirror of https://github.com/ArduPilot/ardupilot
Tracker: move data stream send up
This commit is contained in:
parent
5674a68457
commit
b46379b3f3
|
@ -315,58 +315,51 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
|
|||
AP_GROUPEND
|
||||
};
|
||||
|
||||
void
|
||||
GCS_MAVLINK_Tracker::data_stream_send(void)
|
||||
{
|
||||
send_queued_parameters();
|
||||
static const uint8_t STREAM_RAW_SENSORS_msgs[] = {
|
||||
MSG_RAW_IMU1, // RAW_IMU, SCALED_IMU2, SCALED_IMU3
|
||||
MSG_RAW_IMU2, // SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3
|
||||
MSG_RAW_IMU3 // SENSOR_OFFSETS
|
||||
};
|
||||
static const uint8_t STREAM_EXTENDED_STATUS_msgs[] = {
|
||||
MSG_EXTENDED_STATUS1, // SYS_STATUS, POWER_STATUS
|
||||
MSG_EXTENDED_STATUS2, // MEMINFO
|
||||
MSG_NAV_CONTROLLER_OUTPUT,
|
||||
MSG_GPS_RAW,
|
||||
MSG_GPS_RTK,
|
||||
MSG_GPS2_RAW,
|
||||
MSG_GPS2_RTK,
|
||||
};
|
||||
static const uint8_t STREAM_POSITION_msgs[] = {
|
||||
MSG_LOCATION,
|
||||
MSG_LOCAL_POSITION
|
||||
};
|
||||
static const uint8_t STREAM_RAW_CONTROLLER_msgs[] = {
|
||||
MSG_SERVO_OUTPUT_RAW,
|
||||
};
|
||||
static const uint8_t STREAM_RC_CHANNELS_msgs[] = {
|
||||
MSG_RADIO_IN
|
||||
};
|
||||
static const uint8_t STREAM_EXTRA1_msgs[] = {
|
||||
MSG_ATTITUDE,
|
||||
};
|
||||
static const uint8_t STREAM_EXTRA3_msgs[] = {
|
||||
MSG_AHRS,
|
||||
MSG_HWSTATUS,
|
||||
MSG_SIMSTATE, // SIMSTATE, AHRS2
|
||||
MSG_MAG_CAL_REPORT,
|
||||
MSG_MAG_CAL_PROGRESS,
|
||||
};
|
||||
|
||||
if (hal.scheduler->in_delay_callback()) {
|
||||
// don't send any other stream types while in the delay callback
|
||||
return;
|
||||
}
|
||||
|
||||
if (stream_trigger(STREAM_RAW_SENSORS)) {
|
||||
send_message(MSG_RAW_IMU1);
|
||||
send_message(MSG_RAW_IMU2);
|
||||
send_message(MSG_RAW_IMU3);
|
||||
}
|
||||
|
||||
if (stream_trigger(STREAM_EXTENDED_STATUS)) {
|
||||
send_message(MSG_EXTENDED_STATUS1);
|
||||
send_message(MSG_EXTENDED_STATUS2);
|
||||
send_message(MSG_NAV_CONTROLLER_OUTPUT);
|
||||
send_message(MSG_GPS_RAW);
|
||||
send_message(MSG_GPS_RTK);
|
||||
send_message(MSG_GPS2_RAW);
|
||||
send_message(MSG_GPS2_RTK);
|
||||
}
|
||||
|
||||
if (stream_trigger(STREAM_POSITION)) {
|
||||
send_message(MSG_LOCATION);
|
||||
send_message(MSG_LOCAL_POSITION);
|
||||
}
|
||||
|
||||
if (stream_trigger(STREAM_RAW_CONTROLLER)) {
|
||||
send_message(MSG_SERVO_OUTPUT_RAW);
|
||||
}
|
||||
|
||||
if (stream_trigger(STREAM_RC_CHANNELS)) {
|
||||
send_message(MSG_RADIO_IN);
|
||||
send_message(MSG_SERVO_OUTPUT_RAW);
|
||||
}
|
||||
|
||||
if (stream_trigger(STREAM_EXTRA1)) {
|
||||
send_message(MSG_ATTITUDE);
|
||||
}
|
||||
|
||||
if (stream_trigger(STREAM_EXTRA3)) {
|
||||
send_message(MSG_AHRS);
|
||||
send_message(MSG_HWSTATUS);
|
||||
send_message(MSG_SIMSTATE);
|
||||
send_message(MSG_MAG_CAL_REPORT);
|
||||
send_message(MSG_MAG_CAL_PROGRESS);
|
||||
}
|
||||
}
|
||||
const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
|
||||
MAV_STREAM_ENTRY(STREAM_RAW_SENSORS),
|
||||
MAV_STREAM_ENTRY(STREAM_EXTENDED_STATUS),
|
||||
MAV_STREAM_ENTRY(STREAM_POSITION),
|
||||
MAV_STREAM_ENTRY(STREAM_RAW_CONTROLLER),
|
||||
MAV_STREAM_ENTRY(STREAM_RC_CHANNELS),
|
||||
MAV_STREAM_ENTRY(STREAM_EXTRA1),
|
||||
MAV_STREAM_ENTRY(STREAM_EXTRA3),
|
||||
MAV_STREAM_TERMINATOR // must have this at end of stream_entries
|
||||
};
|
||||
|
||||
/*
|
||||
We eavesdrop on MAVLINK_MSG_ID_GLOBAL_POSITION_INT and
|
||||
|
|
|
@ -7,8 +7,6 @@ class GCS_MAVLINK_Tracker : public GCS_MAVLINK
|
|||
|
||||
public:
|
||||
|
||||
void data_stream_send(void) override;
|
||||
|
||||
protected:
|
||||
|
||||
// telem_delay is not used by Tracker but is pure virtual, thus
|
||||
|
|
Loading…
Reference in New Issue