diff --git a/generator/C/include_v0.9/protocol.h b/generator/C/include_v0.9/protocol.h index 712fea68d..be4312596 100644 --- a/generator/C/include_v0.9/protocol.h +++ b/generator/C/include_v0.9/protocol.h @@ -34,6 +34,14 @@ #define MAVLINK_END_UART_SEND(chan, length) #endif +/* + to get warnings when any WIP message is used, add this: + #define MAVLINK_WIP __attribute__((warning("MAVLink work in progress"))) +*/ +#ifndef MAVLINK_WIP +#define MAVLINK_WIP +#endif + #ifdef MAVLINK_SEPARATE_HELPERS #define MAVLINK_HELPER #else diff --git a/generator/C/include_v1.0/protocol.h b/generator/C/include_v1.0/protocol.h index 34749d9ba..d211790c3 100644 --- a/generator/C/include_v1.0/protocol.h +++ b/generator/C/include_v1.0/protocol.h @@ -34,6 +34,14 @@ #define MAVLINK_END_UART_SEND(chan, length) #endif +/* + to get warnings when any WIP message is used, add this: + #define MAVLINK_WIP __attribute__((warning("MAVLink work in progress"))) +*/ +#ifndef MAVLINK_WIP +#define MAVLINK_WIP +#endif + /* option to provide alternative implementation of mavlink_helpers.h */ #ifdef MAVLINK_SEPARATE_HELPERS diff --git a/generator/C/include_v2.0/protocol.h b/generator/C/include_v2.0/protocol.h index d9227303f..dfbbe6ea3 100644 --- a/generator/C/include_v2.0/protocol.h +++ b/generator/C/include_v2.0/protocol.h @@ -33,6 +33,14 @@ #define MAVLINK_END_UART_SEND(chan, length) #endif +/* + to get warnings when any WIP message is used, add this: + #define MAVLINK_WIP __attribute__((warning("MAVLink work in progress"))) +*/ +#ifndef MAVLINK_WIP +#define MAVLINK_WIP +#endif + /* option to provide alternative implementation of mavlink_helpers.h */ #ifdef MAVLINK_SEPARATE_HELPERS diff --git a/generator/mavgen_c.py b/generator/mavgen_c.py index 5d61394d3..eea1c4265 100644 --- a/generator/mavgen_c.py +++ b/generator/mavgen_c.py @@ -170,6 +170,10 @@ def generate_main_h(directory, xml): def generate_message_h(directory, m): '''generate per-message header for a XML file''' + if m.wip: + m.MSG_ATTRIBUTE = 'MAVLINK_WIP\n' + else: + m.MSG_ATTRIBUTE = '' f = open(os.path.join(directory, 'mavlink_msg_%s.h' % m.name_lower), mode='w') t.write(f, ''' #pragma once @@ -221,7 +225,7 @@ def generate_message_h(directory, m): }} * @return length of the message in bytes (excluding serial stream start sign) */ -static inline uint16_t mavlink_msg_${name_lower}_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, +${MSG_ATTRIBUTE}static inline uint16_t mavlink_msg_${name_lower}_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, ${{arg_fields: ${array_const}${type} ${array_prefix}${name},}}) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS @@ -254,7 +258,7 @@ def generate_message_h(directory, m): }} * @return length of the message in bytes (excluding serial stream start sign) */ -static inline uint16_t mavlink_msg_${name_lower}_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, +${MSG_ATTRIBUTE}static inline uint16_t mavlink_msg_${name_lower}_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, ${{arg_fields:${array_const}${type} ${array_prefix}${name},}}) { @@ -286,7 +290,7 @@ def generate_message_h(directory, m): * @param msg The MAVLink message to compress the data into * @param ${name_lower} C-struct to read the message contents from */ -static inline uint16_t mavlink_msg_${name_lower}_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_${name_lower}_t* ${name_lower}) +${MSG_ATTRIBUTE}static inline uint16_t mavlink_msg_${name_lower}_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_${name_lower}_t* ${name_lower}) { return mavlink_msg_${name_lower}_pack(system_id, component_id, msg,${{arg_fields: ${name_lower}->${name},}}); } @@ -300,7 +304,7 @@ def generate_message_h(directory, m): * @param msg The MAVLink message to compress the data into * @param ${name_lower} C-struct to read the message contents from */ -static inline uint16_t mavlink_msg_${name_lower}_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_${name_lower}_t* ${name_lower}) +${MSG_ATTRIBUTE}static inline uint16_t mavlink_msg_${name_lower}_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_${name_lower}_t* ${name_lower}) { return mavlink_msg_${name_lower}_pack_chan(system_id, component_id, chan, msg,${{arg_fields: ${name_lower}->${name},}}); } @@ -314,7 +318,7 @@ def generate_message_h(directory, m): */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -static inline void mavlink_msg_${name_lower}_send(mavlink_channel_t chan,${{arg_fields: ${array_const}${type} ${array_prefix}${name},}}) +${MSG_ATTRIBUTE}static inline void mavlink_msg_${name_lower}_send(mavlink_channel_t chan,${{arg_fields: ${array_const}${type} ${array_prefix}${name},}}) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_${name}_LEN]; @@ -338,7 +342,7 @@ def generate_message_h(directory, m): * @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}) +${MSG_ATTRIBUTE}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},}}); @@ -355,7 +359,7 @@ def generate_message_h(directory, m): 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},}}) +${MSG_ATTRIBUTE}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; @@ -385,7 +389,7 @@ def generate_message_h(directory, m): * * @return ${units} ${description} */ -static inline ${return_type} mavlink_msg_${name_lower}_get_${name}(const mavlink_message_t* msg${get_arg}) +${MSG_ATTRIBUTE}static inline ${return_type} mavlink_msg_${name_lower}_get_${name}(const mavlink_message_t* msg${get_arg}) { return _MAV_RETURN_${type}${array_tag}(msg, ${array_return_arg} ${wire_offset}); } @@ -397,7 +401,7 @@ def generate_message_h(directory, m): * @param msg The message to decode * @param ${name_lower} C-struct to decode the message contents into */ -static inline void mavlink_msg_${name_lower}_decode(const mavlink_message_t* msg, mavlink_${name_lower}_t* ${name_lower}) +${MSG_ATTRIBUTE}static inline void mavlink_msg_${name_lower}_decode(const mavlink_message_t* msg, mavlink_${name_lower}_t* ${name_lower}) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS ${{ordered_fields: ${decode_left}mavlink_msg_${name_lower}_get_${name}(msg${decode_right});