From 65bbf369da3a4ad123e6677e19bcbc17c5fad7c9 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 19 Oct 2022 14:51:36 +1100 Subject: [PATCH 1/4] MAVLink defines topic --- en/SUMMARY.md | 1 + en/mavgen_c/defines.md | 31 +++++++++++++++++++++++++++++++ 2 files changed, 32 insertions(+) create mode 100644 en/mavgen_c/defines.md diff --git a/en/SUMMARY.md b/en/SUMMARY.md index c929c2f52..3ae811ebe 100644 --- a/en/SUMMARY.md +++ b/en/SUMMARY.md @@ -11,6 +11,7 @@ * [Using MAVLink Libraries](getting_started/use_libraries.md) * [C (mavgen)](mavgen_c/README.md) * [Message Signing](mavgen_c/message_signing_c.md) + * [C Defines](mavgen_c/defines.md) * [Examples](mavgen_c/examples.md) * [UART Interface (C)](mavgen_c/example_c_uart.md) * [UDP Example (C)](mavgen_c/example_c_udp.md) diff --git a/en/mavgen_c/defines.md b/en/mavgen_c/defines.md new file mode 100644 index 000000000..c0580f9fd --- /dev/null +++ b/en/mavgen_c/defines.md @@ -0,0 +1,31 @@ +# MAVLink C Library #defines + +The following C `#defines` can be set in code in order to tune the setup for use on different platforms. + +- `MAVLINK_USE_CONVENIENCE_FUNCTIONS` ([protocol.h](https://github.com/ArduPilot/pymavlink/blob/master/generator/C/include_v2.0/protocol.h)): Causes convenience functions to be defined, including: `_mav_finalize_message_chan_send()`, `_mavlink_send_uart()`, `_mavlink_resend_uart()`. To use, add `#define MAVLINK_USE_CONVENIENCE_FUNCTIONS` to your code. +- `MAVLINK_COMM_NUM_BUFFERS`: Sets the maximum number of comms buffers to be used (comms channels). + By default this is set to 16 on Linux, Windows and macOS, and to 4 on other platforms. + You might set `#define MAVLINK_COMM_NUM_BUFFERS 2` on an embedded system that would only ever have two channels, in order to reduce memory overheads. + A stack overrun will occur if there are more buffers used than allocated. + See [FAQ > How can I further reduce the generated C library size?](../about/faq.md#developers). +- `MAVLINK_SIGNING_FLAG_SIGN_OUTGOING` ([mavlink_types.h](https://github.com/ArduPilot/pymavlink/blob/master/generator/C/include_v2.0/mavlink_types.h)): Enable/disable outgoing signing. + See [Enabling Signing on a Channel > Enabling Signing on a Channel](../mavgen_c/message_signing_c.md#enabling_signing_channel) +- `MAVLINK_EXTERNAL_RX_STATUS` ([mavlink_helpers.h](https://github.com/ArduPilot/pymavlink/blob/master/generator/C/include_v2.0/mavlink_helpers.h)): `mavlink_status_t* mavlink_get_channel_status(uint8_t chan)` returns the status of a particular channel using a preallocated array. + Define `MAVLINK_EXTERNAL_RX_STATUS` if you want to use your own external array (named `m_mavlink_status`) of `mavlink_status_t` objects. +- `MAVLINK_EXTERNAL_RX_BUFFER` ([mavlink_helpers.h](https://github.com/ArduPilot/pymavlink/blob/master/generator/C/include_v2.0/mavlink_helpers.h)): Set if you want to define your own channel comms buffers. + If you define this you will need to declare an array of `mavlink_message_t` (one for each channel) named `m_mavlink_buffer`. +- `NATIVE_BIG_ENDIAN` ([protocol.h](https://github.com/ArduPilot/pymavlink/blob/master/generator/C/include_v2.0/protocol.h)): Enable if using MAVLink on a system that is native big-endian (MAVLINK_LITTLE_ENDIAN is true by default). +- `MAVLINK_SEPARATE_HELPERS` ([protocol.h](https://github.com/ArduPilot/pymavlink/blob/master/generator/C/include_v2.0/protocol.h)): Set to remove all the helpers declared `mavlink_helpers.h`, allowing you to provide an alternative implementation. +- `MAVLINK_MAX_PAYLOAD_LEN`: Override the maximum payload length. + The default maximum payload length is 255 bytes. With care you can override this to reduce memory usage. + For example, to reduce the maximum payload to the smallest size supported by a dialect you could do: + + ```c + #include + #define MAVLINK_MAX_PAYLOAD_LEN MAVLINK_MAX_DIALECT_PAYLOAD_SIZE + ``` + + See also [FAQ > How can I further reduce the generated C library size?](../about/faq.md#developers). + + +There are a number of other internal defines that should not be modified. From d3e884229a9cd4de35fcd9f4d35ee1dbd20f8812 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 26 Oct 2022 09:22:27 +1100 Subject: [PATCH 2/4] Apply suggestions from code review Co-authored-by: Julian Oes --- en/mavgen_c/defines.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/en/mavgen_c/defines.md b/en/mavgen_c/defines.md index c0580f9fd..ef643e137 100644 --- a/en/mavgen_c/defines.md +++ b/en/mavgen_c/defines.md @@ -10,9 +10,9 @@ The following C `#defines` can be set in code in order to tune the setup for use See [FAQ > How can I further reduce the generated C library size?](../about/faq.md#developers). - `MAVLINK_SIGNING_FLAG_SIGN_OUTGOING` ([mavlink_types.h](https://github.com/ArduPilot/pymavlink/blob/master/generator/C/include_v2.0/mavlink_types.h)): Enable/disable outgoing signing. See [Enabling Signing on a Channel > Enabling Signing on a Channel](../mavgen_c/message_signing_c.md#enabling_signing_channel) -- `MAVLINK_EXTERNAL_RX_STATUS` ([mavlink_helpers.h](https://github.com/ArduPilot/pymavlink/blob/master/generator/C/include_v2.0/mavlink_helpers.h)): `mavlink_status_t* mavlink_get_channel_status(uint8_t chan)` returns the status of a particular channel using a preallocated array. +- `MAVLINK_EXTERNAL_RX_STATUS` ([mavlink_helpers.h](https://github.com/ArduPilot/pymavlink/blob/master/generator/C/include_v2.0/mavlink_helpers.h)): `mavlink_status_t* mavlink_get_channel_status(uint8_t chan)` returns the status of a particular channel using a preallocated `static` array. Define `MAVLINK_EXTERNAL_RX_STATUS` if you want to use your own external array (named `m_mavlink_status`) of `mavlink_status_t` objects. -- `MAVLINK_EXTERNAL_RX_BUFFER` ([mavlink_helpers.h](https://github.com/ArduPilot/pymavlink/blob/master/generator/C/include_v2.0/mavlink_helpers.h)): Set if you want to define your own channel comms buffers. +- `MAVLINK_EXTERNAL_RX_BUFFER` ([mavlink_helpers.h](https://github.com/ArduPilot/pymavlink/blob/master/generator/C/include_v2.0/mavlink_helpers.h)): Set if you want to define your own channel comms buffers on the stack or heap, rather than using the pre-allocated `static` buffers. If you define this you will need to declare an array of `mavlink_message_t` (one for each channel) named `m_mavlink_buffer`. - `NATIVE_BIG_ENDIAN` ([protocol.h](https://github.com/ArduPilot/pymavlink/blob/master/generator/C/include_v2.0/protocol.h)): Enable if using MAVLink on a system that is native big-endian (MAVLINK_LITTLE_ENDIAN is true by default). - `MAVLINK_SEPARATE_HELPERS` ([protocol.h](https://github.com/ArduPilot/pymavlink/blob/master/generator/C/include_v2.0/protocol.h)): Set to remove all the helpers declared `mavlink_helpers.h`, allowing you to provide an alternative implementation. From 4a0d389fd1b1e658424cc84745f2b130d3946605 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 26 Oct 2022 09:24:26 +1100 Subject: [PATCH 3/4] Update en/mavgen_c/defines.md --- en/mavgen_c/defines.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/en/mavgen_c/defines.md b/en/mavgen_c/defines.md index ef643e137..ef8a00db8 100644 --- a/en/mavgen_c/defines.md +++ b/en/mavgen_c/defines.md @@ -17,7 +17,7 @@ The following C `#defines` can be set in code in order to tune the setup for use - `NATIVE_BIG_ENDIAN` ([protocol.h](https://github.com/ArduPilot/pymavlink/blob/master/generator/C/include_v2.0/protocol.h)): Enable if using MAVLink on a system that is native big-endian (MAVLINK_LITTLE_ENDIAN is true by default). - `MAVLINK_SEPARATE_HELPERS` ([protocol.h](https://github.com/ArduPilot/pymavlink/blob/master/generator/C/include_v2.0/protocol.h)): Set to remove all the helpers declared `mavlink_helpers.h`, allowing you to provide an alternative implementation. - `MAVLINK_MAX_PAYLOAD_LEN`: Override the maximum payload length. - The default maximum payload length is 255 bytes. With care you can override this to reduce memory usage. + The default maximum payload length is 255 bytes. With care you can override this to reduce the size, and hence memory usage (note, the maximum size cannot be increased as it is stored in a `uint8_t). For example, to reduce the maximum payload to the smallest size supported by a dialect you could do: ```c From be056f85f914d8a0c3d610d71ef4e1b82efc1927 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 3 Nov 2022 08:55:54 +1100 Subject: [PATCH 4/4] Update en/mavgen_c/defines.md --- en/mavgen_c/defines.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/en/mavgen_c/defines.md b/en/mavgen_c/defines.md index ef8a00db8..980cfbd19 100644 --- a/en/mavgen_c/defines.md +++ b/en/mavgen_c/defines.md @@ -2,7 +2,8 @@ The following C `#defines` can be set in code in order to tune the setup for use on different platforms. -- `MAVLINK_USE_CONVENIENCE_FUNCTIONS` ([protocol.h](https://github.com/ArduPilot/pymavlink/blob/master/generator/C/include_v2.0/protocol.h)): Causes convenience functions to be defined, including: `_mav_finalize_message_chan_send()`, `_mavlink_send_uart()`, `_mavlink_resend_uart()`. To use, add `#define MAVLINK_USE_CONVENIENCE_FUNCTIONS` to your code. +- `MAVLINK_USE_CONVENIENCE_FUNCTIONS` ([protocol.h](https://github.com/ArduPilot/pymavlink/blob/master/generator/C/include_v2.0/protocol.h)): Causes convenience functions to be defined, including: `_mav_finalize_message_chan_send()`, `_mavlink_send_uart()`, `_mavlink_resend_uart()`. + Library users may choose not to set this and roll out their own implementations for efficiency (or other) reasons. - `MAVLINK_COMM_NUM_BUFFERS`: Sets the maximum number of comms buffers to be used (comms channels). By default this is set to 16 on Linux, Windows and macOS, and to 4 on other platforms. You might set `#define MAVLINK_COMM_NUM_BUFFERS 2` on an embedded system that would only ever have two channels, in order to reduce memory overheads.