Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

mavlink_helpers: send one mavlink packet per uart write #353

Closed
wants to merge 1 commit into from

Conversation

MaEtUgR
Copy link
Contributor

@MaEtUgR MaEtUgR commented Sep 9, 2019

Most of the diff just consists of spacings because there were trailing spaces, mixed indentation, ...

The actual change is readability and how the function _mav_finalize_message_chan_send operates.

Before: It independently handled all the message parts magic number (size +1 everywhere), header, payload, crc, signature independently and also sent them independently each with a system call to the hardware. This saved one payload size of stack during the function call because the payload did need space in the buffer but had the disadvantage of 3-4 system calls to the UART and possibly even fragmentation of messages in the various applications the different users come up with like using the same UART for other protocols at the same time or forwarding the bytes over UDP without reparsing.

New: That's why I suggest to fill up one buffer per message and sending it all at once. I made an effort to make the implementation as readable, efficient and compatible as possible. I'm aware that there are other functions in the same helper which are partly duplicate and would also need adjustment. The calculation of the signature can still be simplified a lot since distinguishing the message parts is not necessary.

Thanks for any feedback.
JFYI @LorenzMeier

@peterbarker
Copy link
Contributor

peterbarker commented Sep 10, 2019 via email

@MaEtUgR
Copy link
Contributor Author

MaEtUgR commented Sep 10, 2019

@peterbarker Thanks for the clarification. I'm guessing that my confusion then comes from all the convenience functions using _mav_finalize_message_chan_send hardcoded

_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_${name}, buf, MAVLINK_MSG_ID_${name}_MIN_LEN, MAVLINK_MSG_ID_${name}_LEN, MAVLINK_MSG_ID_${name}_CRC);
#else
mavlink_${name_lower}_t packet;
${{scalar_fields: packet.${name} = ${putname};
}}
${{array_fields: mav_array_memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length});
}}
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_${name}, (const char *)&packet, MAVLINK_MSG_ID_${name}_MIN_LEN, MAVLINK_MSG_ID_${name}_LEN, MAVLINK_MSG_ID_${name}_CRC);
#endif
}
/**
* @brief Send a ${name_lower} message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_${name_lower}_send_struct(mavlink_channel_t chan, const mavlink_${name_lower}_t* ${name_lower})
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_${name_lower}_send(chan,${{arg_fields: ${name_lower}->${name},}});
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_${name}, (const char *)${name_lower}, MAVLINK_MSG_ID_${name}_MIN_LEN, MAVLINK_MSG_ID_${name}_LEN, MAVLINK_MSG_ID_${name}_CRC);
#endif
}
#if MAVLINK_MSG_ID_${name}_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_${name_lower}_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, ${{arg_fields: ${array_const}${type} ${array_prefix}${name},}})
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
${{scalar_fields: _mav_put_${type}(buf, ${wire_offset}, ${putname});
}}
${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length});
}}
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_${name}, buf, MAVLINK_MSG_ID_${name}_MIN_LEN, MAVLINK_MSG_ID_${name}_LEN, MAVLINK_MSG_ID_${name}_CRC);
#else
mavlink_${name_lower}_t *packet = (mavlink_${name_lower}_t *)msgbuf;
${{scalar_fields: packet->${name} = ${putname};
}}
${{array_fields: mav_array_memcpy(packet->${name}, ${name}, sizeof(${type})*${array_length});
}}
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_${name}, (const char *)packet, MAVLINK_MSG_ID_${name}_MIN_LEN, MAVLINK_MSG_ID_${name}_LEN, MAVLINK_MSG_ID_${name}_CRC);
So it's either convenience or one UART access per message?

@peterbarker
Copy link
Contributor

peterbarker commented Sep 10, 2019 via email

@jkflying
Copy link

@peterbarker it would be a maximum of 256 extra bytes, wouldn't it? I know we operate in resource constrained environments, but this is potentially a pretty serious issue on the receiving side, since it is generally a non-preemptive OS that could now require multiple time slices to handle a single message instead of 1. Something like a Raspberry Pi Zero would notice the difference, and depending on implementation, across a network each _mavlink_send_uart might get its own UDP packet as well, ie. a whole UDP packet for 2B of CRC data.


There's also a slightly different approach: add another helper to get the prefix and suffix length on the message, then the caller can allocate the extra space and position their data correctly in the packet buffer. packet then gets the headers and crc (and maybe signature) added into its buffer, and gets sent.

It would end up being an extra ~2 lines of code on the caller side, wouldn't have any extra memory requirements, and we still get the benefits of just doing a single _mavlink_send_uart (which is what we're really trying to achieve here).

This would need to be another function that gets added though, so we don't break the API.

@MaEtUgR
Copy link
Contributor Author

MaEtUgR commented Sep 15, 2019

Closing this since it appears to be not the expected way to solve the still unsolved problem. For anyone following the discussion I made an issue here: PX4/PX4-Autopilot#12957

@MaEtUgR MaEtUgR closed this Sep 15, 2019
@MaEtUgR MaEtUgR deleted the one-packet-per-write branch July 31, 2024 08:15
@MaEtUgR MaEtUgR restored the one-packet-per-write branch July 31, 2024 08:19
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants