forked from Archive/PX4-Autopilot
ulog stream msgs: rename 'sequence' fields as they are protected names in fastrtpsgen
This commit is contained in:
parent
88a7e3df09
commit
10e3bcd138
|
@ -12,7 +12,7 @@ uint8 FLAGS_NEED_ACK = 1 # if set, this message requires to be acked.
|
|||
uint8 length # length of data
|
||||
uint8 first_message_offset # offset into data where first message starts. This
|
||||
# can be used for recovery, when a previous message got lost
|
||||
uint16 sequence # allows determine drops
|
||||
uint16 msg_sequence # allows determine drops
|
||||
uint8 flags # see FLAGS_*
|
||||
uint8[249] data # ulog data
|
||||
|
||||
|
|
|
@ -5,4 +5,4 @@ uint64 timestamp # time since system start (microseconds)
|
|||
int32 ACK_TIMEOUT = 50 # timeout waiting for an ack until we retry to send the message [ms]
|
||||
int32 ACK_MAX_TRIES = 50 # maximum amount of tries to (re-)send a message, each time waiting ACK_TIMEOUT ms
|
||||
|
||||
uint16 sequence
|
||||
uint16 msg_sequence
|
||||
|
|
|
@ -72,7 +72,7 @@ void LogWriterMavlink::start_log()
|
|||
ulog_stream_ack_s ack;
|
||||
orb_copy(ORB_ID(ulog_stream_ack), _ulog_stream_ack_sub, &ack);
|
||||
|
||||
_ulog_stream_data.sequence = 0;
|
||||
_ulog_stream_data.msg_sequence = 0;
|
||||
_ulog_stream_data.length = 0;
|
||||
_ulog_stream_data.first_message_offset = 0;
|
||||
|
||||
|
@ -160,7 +160,7 @@ int LogWriterMavlink::publish_message()
|
|||
ulog_stream_ack_s ack;
|
||||
orb_copy(ORB_ID(ulog_stream_ack), _ulog_stream_ack_sub, &ack);
|
||||
|
||||
if (ack.sequence == _ulog_stream_data.sequence) {
|
||||
if (ack.msg_sequence == _ulog_stream_data.msg_sequence) {
|
||||
got_ack = true;
|
||||
}
|
||||
|
||||
|
@ -178,7 +178,7 @@ int LogWriterMavlink::publish_message()
|
|||
PX4_DEBUG("got ack in %i ms", (int)(hrt_elapsed_time(&started) / 1000));
|
||||
}
|
||||
|
||||
_ulog_stream_data.sequence++;
|
||||
_ulog_stream_data.msg_sequence++;
|
||||
_ulog_stream_data.length = 0;
|
||||
_ulog_stream_data.first_message_offset = 255;
|
||||
return 0;
|
||||
|
|
|
@ -116,7 +116,7 @@ int MavlinkULog::handle_update(mavlink_channel_t channel)
|
|||
const ulog_stream_s &ulog_data = _ulog_stream_sub.get();
|
||||
|
||||
mavlink_logging_data_acked_t msg;
|
||||
msg.sequence = ulog_data.sequence;
|
||||
msg.sequence = ulog_data.msg_sequence;
|
||||
msg.length = ulog_data.length;
|
||||
msg.first_message_offset = ulog_data.first_message_offset;
|
||||
msg.target_system = _target_system;
|
||||
|
@ -140,12 +140,12 @@ int MavlinkULog::handle_update(mavlink_channel_t channel)
|
|||
_sent_tries = 1;
|
||||
_last_sent_time = hrt_absolute_time();
|
||||
lock();
|
||||
_wait_for_ack_sequence = ulog_data.sequence;
|
||||
_wait_for_ack_sequence = ulog_data.msg_sequence;
|
||||
_ack_received = false;
|
||||
unlock();
|
||||
|
||||
mavlink_logging_data_acked_t msg;
|
||||
msg.sequence = ulog_data.sequence;
|
||||
msg.sequence = ulog_data.msg_sequence;
|
||||
msg.length = ulog_data.length;
|
||||
msg.first_message_offset = ulog_data.first_message_offset;
|
||||
msg.target_system = _target_system;
|
||||
|
@ -155,7 +155,7 @@ int MavlinkULog::handle_update(mavlink_channel_t channel)
|
|||
|
||||
} else {
|
||||
mavlink_logging_data_t msg;
|
||||
msg.sequence = ulog_data.sequence;
|
||||
msg.sequence = ulog_data.msg_sequence;
|
||||
msg.length = ulog_data.length;
|
||||
msg.first_message_offset = ulog_data.first_message_offset;
|
||||
msg.target_system = _target_system;
|
||||
|
@ -252,7 +252,7 @@ void MavlinkULog::publish_ack(uint16_t sequence)
|
|||
{
|
||||
ulog_stream_ack_s ack;
|
||||
ack.timestamp = hrt_absolute_time();
|
||||
ack.sequence = sequence;
|
||||
ack.msg_sequence = sequence;
|
||||
|
||||
_ulog_stream_ack_pub.publish(ack);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue