uint8[<=255] certificate_of_authenticity in the HardwareVersion field, and uint8[<=80] name. The resulting ambiguity in the payload length can however not be resolved from the payload length itself. So, question is: How, if a CA is present is one supposed to determine the lengths of these two fields?--
You received this message because you are subscribed to the Google Groups "UAVCAN" group.
To unsubscribe from this group and stop receiving emails from it, send an email to uavcan+unsubscribe@googlegroups.com.
To post to this group, send email to uav...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/uavcan/bd700165-9cb2-4132-a816-be1e88983cb5%40googlegroups.com.
For more options, visit https://groups.google.com/d/optout.
uavcan.protocol.RestartNode.It is not clear to me if after the restart the node is supposed to "forget" its ID in case it was allocated dynamically, such that the allocation needs to be repeated, or to keep it but just so to say restart everything else ?I wanted to add, the above list you offered is invaluable ! THX !
--
You received this message because you are subscribed to the Google Groups "UAVCAN" group.
To unsubscribe from this group and stop receiving emails from it, send an email to uavcan+un...@googlegroups.com.
To post to this group, send email to uav...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/uavcan/23dc8d2e-9bc2-4964-b65b-e0488223e7f6%40googlegroups.com.
static const uint32_t AllTME = CANARD_STM32_CAN_TSR_TME0 | CANARD_STM32_CAN_TSR_TME1 | CANARD_STM32_CAN_TSR_TME2;
while( canardPeekTxQueue(&ins)!= NULL ){};
while( (BXCAN->TSR & AllTME) != AllTME ){};
ReBoot();
--
You received this message because you are subscribed to the Google Groups "UAVCAN" group.
To unsubscribe from this group and stop receiving emails from it, send an email to uavcan+un...@googlegroups.com.
To post to this group, send email to uav...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/uavcan/59de056e-c5d4-47bd-aae0-6be13ed4fd1e%40googlegroups.com.
except that your first loop will never end unless you flush the queue within its body
--
You received this message because you are subscribed to the Google Groups "UAVCAN" group.
To unsubscribe from this group and stop receiving emails from it, send an email to uavcan+un...@googlegroups.com.
To post to this group, send email to uav...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/uavcan/ed73ea35-ebc9-4204-8ec4-0f73c11fbbcd%40googlegroups.com.
I don't foresee any significant improvements in performance
Someone should volunteer to research this issue in a more detailed way.
To view this discussion on the web visit https://groups.google.com/d/msgid/uavcan/57bde681-ec62-4934-b762-84f38d3d834d%40googlegroups.com.
--
You received this message because you are subscribed to the Google Groups "UAVCAN" group.
To unsubscribe from this group and stop receiving emails from it, send an email to uavcan+unsubscribe@googlegroups.com.
To post to this group, send email to uav...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/uavcan/cc61b11a-4f91-4ead-a784-fbbf1c5869be%40googlegroups.com.
You can refer to libuavcan or pyuavcan to see how to handle variable length fields properly. In the specific case of gnss.Fix, the length field of the last array is omitted because it is the last variable length field of the message. See "tail array optimization".
You can only set zero the fields "timestamp" and "num_leap_seconds". The other two must be populated properly as follows:- gnss_timestamp - GNSS time provided by the receiver.- gnss_time_standard - according to the time base reported by the receiver (usually UTC or GPS time).
# # Time solution. # Time standard (GPS, UTC, TAI, etc) is defined in the field below. # uavcan.Timestamp gnss_timestamp # GNSS timestamp, if available, otherwise zero # # Time standard used in the GNSS timestamp field. # uint3 GNSS_TIME_STANDARD_NONE = 0 # Time is unknown uint3 GNSS_TIME_STANDARD_TAI = 1 uint3 GNSS_TIME_STANDARD_UTC = 2 uint3 GNSS_TIME_STANDARD_GPS = 3 uint3 gnss_time_standard
you could update that. :)
Cheers, Olli
--
You received this message because you are subscribed to the Google Groups "UAVCAN" group.
To unsubscribe from this group and stop receiving emails from it, send an email to uavcan+unsubscribe@googlegroups.com.
To post to this group, send email to uav...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/uavcan/3e3aa359-123d-41b9-a35c-5f2e994f1edd%40googlegroups.com.
GNSS_TIME_STANDARD_UTC = 2The timestamp is derived from the current UTC time minus UTC 1.1.1970. Leap seconds are taken into account. For convenience, the field leap_seconds reports the number of leap seconds with respect to Unix time, if the value is non zero.GNSS_TIME_STANDARD_UNIX = 4The timestamp corresponds to Unix time. Leap seconds are not taken into account. For convenience, the field leap_seconds reports the number of leap seconds between UTC and Unix time, if the value is non zero.GNSS_TIME_STANDARD_GPS = 3For convenience, the field leap_seconds reports the number of leap seconds between GPS time and Unix time, if the value is non zero. GNSS_TIME_STANDARD_GPS I would have appreciated a clear definition. I assume that it is supposed to be --
You received this message because you are subscribed to the Google Groups "UAVCAN" group.
To unsubscribe from this group and stop receiving emails from it, send an email to uavcan+unsubscribe@googlegroups.com.
To post to this group, send email to uav...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/uavcan/32ec14cd-9626-48e4-994f-304803b9483e%40googlegroups.com.
GNSS_TIME_STANDARD_UNIX = 4. Or I guess, to rename to GNSS_TIME_STANDARD_UNIX = 2, and GNSS_TIME_STANDARD_UTC = 4. One of my points was that if it's not UTC it should not be called UTC. I
also did not understand "The GPS timestamp is implicitly defined
likewise". Is this implying that the formula I gave is not what it is
supposed to be, but that it somehow is dated back to Unix epoche?GNSS_TIME_STANDARD_XXX options ...--
You received this message because you are subscribed to the Google Groups "UAVCAN" group.
To unsubscribe from this group and stop receiving emails from it, send an email to uavcan+unsubscribe@googlegroups.com.
To post to this group, send email to uav...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/uavcan/4de68215-c854-4aa4-9bf1-b19d853b00dc%40googlegroups.com.
\r\n ". I read this to mean "any arbitrary" sequence of said characters terminated with \r\n. But that's then impossible to parse without a timeout or other clumsy mechanism to distinguish between the \r end of SLCAN commands and \r\n end of the cli commands (my argument hinges on the fact that this statement "The fact that CLI commands and their responses are terminated with \r\n rather than plain \r
can be used to distinguish SLCAN data from CLI data in real time." is not working in practice, at an \r you need to wait for the next character to see if you can terminate, which however might come very late, or never). I thus looked into the babel code to see how you possibly could have resolved that penalty, and - if I got it right - you do that by ignoring the \n and also take \r as termination of a cli command, and then parse for the START of the message! So, (1) the statement in the docs is incorrect, (2) it's IMHO a most unfortunate specification = requires an "ugly" parser (I know a bit about parsers/languages/compilers).--
You received this message because you are subscribed to the Google Groups "UAVCAN" group.
To unsubscribe from this group and stop receiving emails from it, send an email to uavcan+unsubscribe@googlegroups.com.
To post to this group, send email to uav...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/uavcan/7179ed3c-05a6-4404-ba53-4be6dfe738bc%40googlegroups.com.
T0123456780102030405060708\r from the cli command T0123456780102030405060708\r\n with zero time penalty in all possible situations. The specification allows that.btw: I think I've at least "sorted" out the AP3.4.6 UAVCAN/PX4 issue ... it seems it doesn't like too inconsistent magnetometers, and freezes when without alert ... whatever, since I have them in better consistency, it runs now for quite a while on my bench ...
--
You received this message because you are subscribed to the Google Groups "UAVCAN" group.
To unsubscribe from this group and stop receiving emails from it, send an email to uavcan+unsubscribe@googlegroups.com.
To post to this group, send email to uav...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/uavcan/70bb3a05-3ce5-4586-ad10-3d665d0bef7e%40googlegroups.com.
\r\n rather than plain \r
can be used to distinguish SLCAN data from CLI data in real time". It is the condition that a cli command must not match a slcan command which allows that. --
You received this message because you are subscribed to the Google Groups "UAVCAN" group.
To unsubscribe from this group and stop receiving emails from it, send an email to uavcan+unsubscribe@googlegroups.com.
To post to this group, send email to uav...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/uavcan/d1766ac1-1743-4129-89ff-2a43b542c8af%40googlegroups.com.