Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 2 additions & 3 deletions comms/mavlink/generating_v1.0_instructions.txt
Original file line number Diff line number Diff line change
@@ -1,13 +1,12 @@
# get the mavlink/mavlink repository
# git clone https://github.com/rosflight/mavlink.git
git clone https://github.com/mavlink/mavlink.git
git clone https://github.com/mavlink/mavlink.git --recursive

# Go to your rosflight_firmware/comms/mavlink folder
# Put the rosflight.xml file there if not already there

# Create the .c/h files from that directory
# If python3 doesn't work try installing future (pip install future).
# If that doesn't work install Python2.7 and run with python2.7 instead.
# If that doesn't work install Python3.8 and run with python3.8 instead.
# in windows:
rmdir /s v1.0
set PYTHONPATH=%PYTHONPATH%;path\to\mavlink\repo && python3 -m pymavlink.tools.mavgen --lang=C --wire-protocol=1.0 --output=./v1.0 rosflight.xml
Expand Down
2 changes: 1 addition & 1 deletion comms/mavlink/mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -260,7 +260,7 @@ void Mavlink::send_sonar(uint8_t system_id,
send_message(msg);
}

void Mavlink::send_status(uint8_t system_id, bool armed, bool failsafe, bool rc_override,
void Mavlink::send_status(uint8_t system_id, bool armed, bool failsafe, uint16_t rc_override,
bool offboard, uint8_t error_code, uint8_t control_mode,
int16_t num_errors, int16_t loop_time_us)
{
Expand Down
2 changes: 1 addition & 1 deletion comms/mavlink/mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ class Mavlink : public CommLinkInterface
void send_sonar(uint8_t system_id,
/* TODO enum type*/ uint8_t type, float range, float max_range,
float min_range) override;
void send_status(uint8_t system_id, bool armed, bool failsafe, bool rc_override, bool offboard,
void send_status(uint8_t system_id, bool armed, bool failsafe, uint16_t rc_override, bool offboard,
uint8_t error_code, uint8_t control_mode, int16_t num_errors,
int16_t loop_time_us) override;
void send_timesync(uint8_t system_id, int64_t tc1, int64_t ts1) override;
Expand Down
27 changes: 2 additions & 25 deletions comms/mavlink/rosflight.xml
Original file line number Diff line number Diff line change
@@ -1,29 +1,6 @@
<?xml version="1.0"?>
<?note
# get the mavlink/mavlink repository
git clone https://github.com/rosflight/mavlink.git

# Go to your rosflight_firmware/comms/mavlink folder
# Put the rosflight.xml file there if not already there

# Create the .c/h files from that directory
# If python3 doesn't work try installing future (pip install future).
# If that doesn't work install Python2.7 and run with python2.7 instead.
# in windows:
rmdir /s v1.0
set PYTHONPATH=%PYTHONPATH%;path\to\mavlink\repo && python3 -m pymavlink.tools.mavgen --lang=C --wire-protocol=1.0 --output=./v1.0 rosflight.xml

# e.g.,
rmdir /s v1.0
set PYTHONPATH=%PYTHONPATH%;C:\Projects\mavlink && python3 -m pymavlink.tools.mavgen --lang=C --wire-protocol=1.0 --output=./v1.0 rosflight.xml

# in Linux:
sudo rm -r ./v1.0
PYTHONPATH=$PYTHONPATH:/path/to/mavlink/repo python3 -m pymavlink.tools.mavgen --lang=C --wire-protocol=1.0 --output=./v1.0 rosflight.xml

# If you are in the mavlink repo environment with rosflight.xml in the standard location:
python3 -m pymavlink.tools.mavgen --lang=C --wire-protocol=1.0 --output=generated/include/mavlink/v1.0 message_definitions/v1.0/rosflight.xml
# copy/paste the v1.0 directory into your rosflight_firmware/comms/mavlink folder
See the generating_v1.0_instructions.txt to regenerate mavlink headers based off this file.
?>
<mavlink>
<enums>
Expand Down Expand Up @@ -283,7 +260,7 @@ python3 -m pymavlink.tools.mavgen --lang=C --wire-protocol=1.0 --output=generate
<description>Flight Status</description>
<field type="uint8_t" name="armed"/>
<field type="uint8_t" name="failsafe"/>
<field type="uint8_t" name="rc_override"/>
<field type="uint16_t" name="rc_override"/>
<field type="uint8_t" name="offboard"/>
<field type="uint8_t" name="error_code" enum="ROSFLIGHT_ERROR_CODE"/>
<field type="uint8_t" name="control_mode" enum="OFFBOARD_CONTROL_MODE"/>
Expand Down
15 changes: 15 additions & 0 deletions comms/mavlink/v1.0/protocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down Expand Up @@ -179,6 +187,13 @@ static inline void byte_copy_8(char *dst, const char *src)
*/
static inline void mav_array_memcpy(void *dest, const void *src, size_t n)
{
// It would be tempting to do a strcpy/strncpy for the char[] type. Unfortunately, some
// existing MAVLink messages such as PARAM_EXT_VALUE.param_value use the char[] type for
// arbitrary data (including null), and would break.
//
// It would be nice to change such char[] types to uint8_t[] but that would change the
// CRC_EXTRA.

if (src == NULL) {
memset(dest, 0, n);
} else {
Expand Down
2 changes: 1 addition & 1 deletion comms/mavlink/v1.0/rosflight/mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#ifndef MAVLINK_H
#define MAVLINK_H

#define MAVLINK_PRIMARY_XML_HASH 9006179629977798615
#define MAVLINK_PRIMARY_XML_HASH 1891770357406712603

#ifndef MAVLINK_STX
#define MAVLINK_STX 254
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -310,7 +310,7 @@ static inline void mavlink_msg_attitude_quaternion_send_struct(mavlink_channel_t

#if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant of _send() can be used to save stack space by re-using
This variant of _send() can be used to save stack space by reusing
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
Expand Down
2 changes: 1 addition & 1 deletion comms/mavlink/v1.0/rosflight/mavlink_msg_diff_pressure.h
Original file line number Diff line number Diff line change
Expand Up @@ -235,7 +235,7 @@ static inline void mavlink_msg_diff_pressure_send_struct(mavlink_channel_t chan,

#if MAVLINK_MSG_ID_DIFF_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant of _send() can be used to save stack space by re-using
This variant of _send() can be used to save stack space by reusing
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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -250,7 +250,7 @@ static inline void mavlink_msg_external_attitude_send_struct(mavlink_channel_t c

#if MAVLINK_MSG_ID_EXTERNAL_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant of _send() can be used to save stack space by re-using
This variant of _send() can be used to save stack space by reusing
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
Expand Down
2 changes: 1 addition & 1 deletion comms/mavlink/v1.0/rosflight/mavlink_msg_heartbeat.h
Original file line number Diff line number Diff line change
Expand Up @@ -276,7 +276,7 @@ static inline void mavlink_msg_heartbeat_send_struct(mavlink_channel_t chan, con

#if MAVLINK_MSG_ID_HEARTBEAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant of _send() can be used to save stack space by re-using
This variant of _send() can be used to save stack space by reusing
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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -310,7 +310,7 @@ static inline void mavlink_msg_offboard_control_send_struct(mavlink_channel_t ch

#if MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant of _send() can be used to save stack space by re-using
This variant of _send() can be used to save stack space by reusing
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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -220,7 +220,7 @@ static inline void mavlink_msg_param_request_list_send_struct(mavlink_channel_t

#if MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant of _send() can be used to save stack space by re-using
This variant of _send() can be used to save stack space by reusing
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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -242,7 +242,7 @@ static inline void mavlink_msg_param_request_read_send_struct(mavlink_channel_t

#if MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant of _send() can be used to save stack space by re-using
This variant of _send() can be used to save stack space by reusing
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
Expand Down
2 changes: 1 addition & 1 deletion comms/mavlink/v1.0/rosflight/mavlink_msg_param_set.h
Original file line number Diff line number Diff line change
Expand Up @@ -257,7 +257,7 @@ static inline void mavlink_msg_param_set_send_struct(mavlink_channel_t chan, con

#if MAVLINK_MSG_ID_PARAM_SET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant of _send() can be used to save stack space by re-using
This variant of _send() can be used to save stack space by reusing
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
Expand Down
2 changes: 1 addition & 1 deletion comms/mavlink/v1.0/rosflight/mavlink_msg_param_value.h
Original file line number Diff line number Diff line change
Expand Up @@ -257,7 +257,7 @@ static inline void mavlink_msg_param_value_send_struct(mavlink_channel_t chan, c

#if MAVLINK_MSG_ID_PARAM_VALUE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant of _send() can be used to save stack space by re-using
This variant of _send() can be used to save stack space by reusing
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
Expand Down
2 changes: 1 addition & 1 deletion comms/mavlink/v1.0/rosflight/mavlink_msg_rc_channels.h
Original file line number Diff line number Diff line change
Expand Up @@ -505,7 +505,7 @@ static inline void mavlink_msg_rc_channels_send_struct(mavlink_channel_t chan, c

#if MAVLINK_MSG_ID_RC_CHANNELS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant of _send() can be used to save stack space by re-using
This variant of _send() can be used to save stack space by reusing
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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -221,7 +221,7 @@ static inline void mavlink_msg_rosflight_aux_cmd_send_struct(mavlink_channel_t c

#if MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant of _send() can be used to save stack space by re-using
This variant of _send() can be used to save stack space by reusing
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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -220,7 +220,7 @@ static inline void mavlink_msg_rosflight_battery_status_send_struct(mavlink_chan

#if MAVLINK_MSG_ID_ROSFLIGHT_BATTERY_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant of _send() can be used to save stack space by re-using
This variant of _send() can be used to save stack space by reusing
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
Expand Down
2 changes: 1 addition & 1 deletion comms/mavlink/v1.0/rosflight/mavlink_msg_rosflight_cmd.h
Original file line number Diff line number Diff line change
Expand Up @@ -205,7 +205,7 @@ static inline void mavlink_msg_rosflight_cmd_send_struct(mavlink_channel_t chan,

#if MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant of _send() can be used to save stack space by re-using
This variant of _send() can be used to save stack space by reusing
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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -220,7 +220,7 @@ static inline void mavlink_msg_rosflight_cmd_ack_send_struct(mavlink_channel_t c

#if MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant of _send() can be used to save stack space by re-using
This variant of _send() can be used to save stack space by reusing
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
Expand Down
2 changes: 1 addition & 1 deletion comms/mavlink/v1.0/rosflight/mavlink_msg_rosflight_gnss.h
Original file line number Diff line number Diff line change
Expand Up @@ -400,7 +400,7 @@ static inline void mavlink_msg_rosflight_gnss_send_struct(mavlink_channel_t chan

#if MAVLINK_MSG_ID_ROSFLIGHT_GNSS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant of _send() can be used to save stack space by re-using
This variant of _send() can be used to save stack space by reusing
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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -250,7 +250,7 @@ static inline void mavlink_msg_rosflight_hard_error_send_struct(mavlink_channel_

#if MAVLINK_MSG_ID_ROSFLIGHT_HARD_ERROR_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant of _send() can be used to save stack space by re-using
This variant of _send() can be used to save stack space by reusing
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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -212,7 +212,7 @@ static inline void mavlink_msg_rosflight_output_raw_send_struct(mavlink_channel_

#if MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant of _send() can be used to save stack space by re-using
This variant of _send() can be used to save stack space by reusing
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
Expand Down
Loading