General questions for confirmation
hamishwillee opened this issue · 7 comments
Confirm:
- High level protocol doesn't do any resending or packet order checking - right? - #83 (comment)
- What general requirements does MAVLink put on resend rates/timeouts for AUTOPILOT_VERSION, HEARTBEAT, SYS_STATUS - see #83 (comment)
- Is Message Profile information useful? - #83 (comment)
- Message extensions - When/why do we use them, and why not everywhere? Assumption is that we use extensions because it is hard to coordinate message changes for existing systems (something we do want to improve going forward). I presume the reason we don't recommend these everywhere (ie drop the idea of reordering) is that there is benefit in reordering and in having the CRCEXTRA as a compatibility check?
CLOSED
- Are
target_sysid
andtarget_compid
part of standard frame in MAVLink 2? - #83 (comment) - No - MAVLink 2 field re-ordering and truncation unclear - #83 (comment)
- Is missionlib useful (status update): #83 (comment) - DELETED
NOTE, some of these might make good FAQs
Edited - CLosed/Fixed. Reordering is same in MAVLink 1 and 2 except for extensions, which are ordered in XML order. We don't have array truncation, just empty field truncation.
MAVLink 2 field re-ordering section might be wrong
MAVLink 2 messages order the MAVLink 1 ("base") fields in the same way as the MAVLink 1 protocol. Extension fields in MAVLink 1 messages, and all fields in new MAVLink 2 messages (id>255), are ordered in the same way as the source XML.
But we also say that we support a simplified version of array truncation - where it sounds like the largest array in the message would have to be moved to the end of the message:
MAVLink 2 truncates any zero (empty) elements at the end of the largest array in a message. Other arrays in the message will not be truncated.
- Can anyone explain the discrepancy?
Further, from @mhkabir I saw:
Mavlink v2 chops off zeros at the end of the payload. This is not a bug. You need to update your C# application to use the v2 parsers.
- Does this happen for every message, or just those with large arrays?
Further we also say:
"MAVLink [v1] reorders internally the message fields according to their size to prevent word / halfword alignment issues "
However MAVLink 2 reorders base ("MAVLink1") fields but keeps any extension fields in XML declaration order.
- Why? Or to put it another way, are we not still concerned about word/half-word issues?
Edited: Closed/Fixed. No. The target is exposed better and is more easily accessible (offset is stored in generated info about each message and so helpers can more easily access this), but is not in defined location in frame.
target_sysid
and target_compid
- are they part of standard frame in MAVLink 2?
target_sysid
andtarget_compid
appear not to be part of the standard packet frame - they are part of the message for those messages that need them:- the Protocol overview indicates incorrectly that they are part of the frame.
- This has propagated into the Serialisation Topic
UPDATE/PARTIAL ANSWER:
This requires more review and docs update, but the short answer is that this is not "wrong". MAVLink 2 attempts to highlight these more clearly and provides better support for implementing these fields.
Specifically these are "optional" fields - they are only in the packet if defined in a point-to-point message. They are in the message payload. However the behaviour is standardised (from here needs checking). They are ALWAYS in the first two slots of the packet area for the message.
The tool provides generic ways to access this info in the "top level" - ie without having to inspect the packet (e.g. in mavlink_types.h
/*
entry in table of information about each message type
*/
typedef struct __mavlink_msg_entry {
uint32_t msgid;
uint8_t crc_extra;
uint8_t msg_len;
uint8_t flags; // MAV_MSG_ENTRY_FLAG_*
uint8_t target_system_ofs; // payload offset to target_system, or 0
uint8_t target_component_ofs; // payload offset to target_component, or 0
} mavlink_msg_entry_t;
FURTHER UPDATE/PARTIAL ANSWER:
Essentially this is incorrect. There is better support in the C library for getting the target system and component ID from a message without having to decode the payload. However that is not the same as saying that the packet format is always going to be in the position shown. Discussion continuing in #91
Does MAVLink protocol at high level does do any resending or packet order checking?
- My understanding is that the Mavlink "core" maintains a sequence number for current sent messages (current_tx_seq). This is added to every message sent and then iterated. It also maintains current received message (current_rx_seq) and stores the next expected message (I think) which is current_rx_seq+1.
- But actual checking of sequence numbers is done in the sub-protocol implementations right?
CLOSED - NOT USEFUL
Is missionlib still useful - do we have a strategy for protocol examples?
See mavlink/mavlink#954
If it is useful then the doc should be linked from the mission and parameter sections
What general requirements does MAVLink put on resend rates/timeouts for AUTOPILOT_VERSION, HEARTBEAT, SYS_STATUS
Old docs indicate they should be sent
- at least rate of 0.1 Hz
- repeatedly independent of the system state.
Questions:
- Is that correct?
- Are these hard rules or "recommendations"?
- Do the autopilots/APIs/GCS have other specific expectations/behaviours. For example, I know that DroneKit sends heartbeat at 1Hz.
- The above covers what autopilots do. What does a GCS or API have to send? - HEARTBEAT (obviously). What else?
- Are there any other messages that must be sent regularly/to some rate? If so what message/rate
Is Message Profile information useful (ie minimum set, for parameters etc?)
NOTE I tend to think that it probably should be in the subprotocol/microservice section) for each service.
Below is docs on profile from old docs.
The minimum message set is intended for barebones operation.
### Autopilot TX
* [HEARTBEAT](../messages/common.md#HEARTBEAT)
* [SYS_STATUS](../messages/common.md#SYS_STATUS)
* [AUTOPILOT_VERSION](../messages/common.md#AUTOPILOT_VERSION)
* [ATTITUDE_QUATERNION](../messages/common.md#ATTITUDE_QUATERNION)
* [GLOBAL_POSITION_INT](../messages/common.md#GLOBAL_POSITION_INT)
* [GPS_RAW_INT](../messages/common.md#GPS_RAW_INT)
* [RC_CHANNELS](../messages/common.md#RC_CHANNELS)
* [BATTERY_STATUS](../messages/common.md#BATTERY_STATUS)
* [HIGHRES_IMU](../messages/common.md#HIGHRES_IMU)
* [STATUSTEXT](../messages/common.md#STATUSTEXT)
### GCS TX
* [HEARTBEAT](../messages/common.md#HEARTBEAT)
* [MANUAL_CONTROL](../messages/common.md#MANUAL_CONTROL)
## Parameter Protocol Profile
In addition to the minimum message profile, the parameter profile requires handling of these messages:
### Autopilot TX
* [PARAM_VALUE](../messages/common.md#PARAM_VALUE)
### GCS TX
* [PARAM_REQUEST_READ](../messages/common.md#PARAM_REQUEST_READ)
* [PARAM_REQUEST_LIST](../messages/common.md#PARAM_REQUEST_LIST)
* [PARAM_SET](../messages/common.md#PARAM_SET)
## Mission Protocol Profile
In addition to the minimum message profile, the mission profile requires handling of these messages:
### Autopilot TX
* [MISSION_ITEM](../messages/common.md#MISSION_ITEM)
* [MISSION_REQUEST_LIST](../messages/common.md#MISSION_REQUEST_LIST)
* [MISSION_CLEAR_ALL](../messages/common.md#MISSION_CLEAR_ALL)
* [MISSION_ITEM_REACHED](../messages/common.md#MISSION_ITEM_REACHED)
* [MISSION_ACK](../messages/common.md#MISSION_ACK)
### GCS TX
* [MISSION_ITEM](../messages/common.md#MISSION_ITEM)
* [MISSION_ITEM_INT](../messages/common.md#MISSION_ITEM_INT) (preferred)
* [MISSION_REQUEST](../messages/common.md#MISSION_REQUEST)
* [MISSION_CURRENT](../messages/common.md#MISSION_CURRENT)
* [MISSION_COUNT](../messages/common.md#MISSION_COUNT)
* [MISSION_ACK](../messages/common.md#MISSION_ACK)
## Robotics / Companion Computer Protocol Profile
In addition to the minimum message profile, the robotics profile requires handling of these messages:
### Autopilot TX
* [SYSTEM_TIME](../messages/common.md#SYSTEM_TIME)
* [ATTITUDE_QUATERNION_CO](../messages/common.md#ATTITUDE_QUATERNION_COV)
* [GLOBAL_POSITION_INT_COV](../messages/common.md#GLOBAL_POSITION_INT_COV)
* [LOCAL_POSITION_NED_COV](../messages/common.md#LOCAL_POSITION_NED_COV)
* [ATTITUDE_TARGET](../messages/common.md#ATTITUDE_TARGET)
* [POSITION_TARGET_LOCAL_NED](../messages/common.md#POSITION_TARGET_LOCAL_NED)
* [POSITION_TARGET_GLOBAL_INT](../messages/common.md#POSITION_TARGET_GLOBAL_INT)
### Companion Computer TX
* [COMMAND_INT](../messages/common.md#COMMAND_INT)
* [SET_ATTITUDE_TARGET](../messages/common.md#SET_ATTITUDE_TARGET)
* [SET_POSITION_TARGET_LOCAL_NED](../messages/common.md#SET_POSITION_TARGET_LOCAL_NED)
* [SET_POSITION_TARGET_GLOBAL_INT](../messages/common.md#SET_POSITION_TARGET_GLOBAL_INT)
These would make sense per microservice, yes. That would be quite educational for implementers.