Hey guys,
I have successfully added a new message into the ArduPlane program, and are using our own ground station to read the messages send down. I noticed however that when I insert the line: gcs_send_message(MSG_THERMO_ATTITUDE) anywhere, the horizon ball now has a 12 second lag to it when I move the ardupilot board around. This lag disappears as soon as I remove the gcs_send_message(MSG_THERMO_ATTITUDE) line.
I have tried putting the line in different speed loops, even in the slow 3 1/3 loop, but still a 12 second delay. I have tried pitting the line in the GCS_Mavlink tab in the following section of code(its at the bottom of the code segment) , but still there is a 12 second delay.
I have run out of ideas for why the message causes this delay. Any ideas would be welcomed. Thanks.
void
GCS_MAVLINK::data_stream_send(void)
{
if (_queued_parameter != NULL) {
if (streamRates[STREAM_PARAMS].get() <= 0) {
streamRates[STREAM_PARAMS].set(50);
}
if (stream_trigger(STREAM_PARAMS)) {
send_message(MSG_NEXT_PARAM);
}
}
if (in_mavlink_delay) {
#if HIL_MODE != HIL_MODE_DISABLED
// in HIL we need to keep sending servo values to ensure
// the simulator doesn't pause, otherwise our sensor
// calibration could stall
if (stream_trigger(STREAM_RAW_CONTROLLER)) {
send_message(MSG_SERVO_OUT);
}
if (stream_trigger(STREAM_RC_CHANNELS)) {
send_message(MSG_RADIO_OUT);
}
#endif
// 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_CURRENT_WAYPOINT);
send_message(MSG_GPS_RAW); // TODO - remove this message after location message is working
send_message(MSG_NAV_CONTROLLER_OUTPUT);
send_message(MSG_FENCE_STATUS);
}
if (stream_trigger(STREAM_POSITION)) {
// sent with GPS read
send_message(MSG_LOCATION);
}
if (stream_trigger(STREAM_RAW_CONTROLLER)) {
send_message(MSG_SERVO_OUT);
}
if (stream_trigger(STREAM_RC_CHANNELS)) {
send_message(MSG_RADIO_OUT);
send_message(MSG_RADIO_IN);
}
if (stream_trigger(STREAM_EXTRA1)) {
send_message(MSG_ATTITUDE);
send_message(MSG_THERMO_ATTITUDE);
//send_message(MSG_SIMSTATE);
}
if (stream_trigger(STREAM_EXTRA2)) {
send_message(MSG_VFR_HUD);
}
if (stream_trigger(STREAM_EXTRA3)) {
send_message(MSG_AHRS);
send_message(MSG_HWSTATUS);
send_message(MSG_WIND);
//send_message(MSG_THERMO_ATTITUDE);
}
}
Replies
Hi, did you do everything right in enum ap_message in defines.h?
It seems to me that something got mixed up en the message deferring buffer in APM. The stuff managed in mavlink_send_message.
Regards
Soren