Show EOL distros:
Package Summary
MAVROS -- MAVLink extendable communication node for ROS with UDP proxy for Ground Control Station.
- Maintainer status: maintained
- Maintainer: Vladimir Ermakov <vooon341 AT gmail DOT com>
- Author: Vladimir Ermakov <vooon341 AT gmail DOT com>
- License: GPLv3
- Bug / feature tracker: https://github.com/mavlink/mavros/issues
- Source: git https://github.com/mavlink/mavros.git (branch: hydro-devel)
Package Summary
MAVROS -- MAVLink extendable communication node for ROS with proxy for Ground Control Station.
- Maintainer status: maintained
- Maintainer: Vladimir Ermakov <vooon341 AT gmail DOT com>
- Author: Vladimir Ermakov <vooon341 AT gmail DOT com>
- License: GPLv3, LGPLv3, BSD
- Bug / feature tracker: https://github.com/mavlink/mavros/issues
- Source: git https://github.com/mavlink/mavros.git (branch: indigo-devel)
Package Summary
MAVROS -- MAVLink extendable communication node for ROS with proxy for Ground Control Station.
- Maintainer status: maintained
- Maintainer: Vladimir Ermakov <vooon341 AT gmail DOT com>
- Author: Vladimir Ermakov <vooon341 AT gmail DOT com>
- License: GPLv3, LGPLv3, BSD
- Bug / feature tracker: https://github.com/mavlink/mavros/issues
- Source: git https://github.com/mavlink/mavros.git (branch: indigo-devel)
Package Summary
MAVROS -- MAVLink extendable communication node for ROS with proxy for Ground Control Station.
- Maintainer status: developed
- Maintainer: Vladimir Ermakov <vooon341 AT gmail DOT com>
- Author: Vladimir Ermakov <vooon341 AT gmail DOT com>
- License: GPLv3, LGPLv3, BSD
- Bug / feature tracker: https://github.com/mavlink/mavros/issues
- Source: git https://github.com/mavlink/mavros.git (branch: master)
Package Summary
MAVROS -- MAVLink extendable communication node for ROS with proxy for Ground Control Station.
- Maintainer status: developed
- Maintainer: Vladimir Ermakov <vooon341 AT gmail DOT com>
- Author: Vladimir Ermakov <vooon341 AT gmail DOT com>
- License: GPLv3, LGPLv3, BSD
- Bug / feature tracker: https://github.com/mavlink/mavros/issues
- Source: git https://github.com/mavlink/mavros.git (branch: master)
Package Summary
MAVROS -- MAVLink extendable communication node for ROS with proxy for Ground Control Station.
- Maintainer status: developed
- Maintainer: Vladimir Ermakov <vooon341 AT gmail DOT com>
- Author: Vladimir Ermakov <vooon341 AT gmail DOT com>
- License: GPLv3, LGPLv3, BSD
- Bug / feature tracker: https://github.com/mavlink/mavros/issues
- Source: git https://github.com/mavlink/mavros.git (branch: master)
Package Summary
MAVROS -- MAVLink extendable communication node for ROS with proxy for Ground Control Station.
- Maintainer status: developed
- Maintainer: Vladimir Ermakov <vooon341 AT gmail DOT com>
- Author: Vladimir Ermakov <vooon341 AT gmail DOT com>
- License: GPLv3, LGPLv3, BSD
- Bug / feature tracker: https://github.com/mavlink/mavros/issues
- Source: git https://github.com/mavlink/mavros.git (branch: master)
Contents
- Overview
- Nodes
- Usage
- Connection URL
- Utility commands
- Plugins
Overview
This package provides communication driver for various autopilots with MAVLink communication protocol. Additional it provides UDP MAVLink bridge for ground control stations (e.g. QGroundControl).
Main node can be extended by plugins (see pluginlib). See also mavros_extras package.
Nodes
mavros_node
main communication node.Subscribed Topics
mavlink/to (mavros_msgs/Mavlink)- Mavlink stream to autopilot.
Published Topics
mavlink/from (mavros_msgs/Mavlink)- Mavlink stream from autopilot.
- Diagnostic status information.
Parameters
~system_id (int, default: 1)- Node MAVLink System ID.
- Node MAVLink Component ID.
- FCU MAVLink System ID.
- FCU MAVLink Component ID.
- Define apply quirk for PX4 or not.
- Alias blacklist (glob syntax, example: ['rc*'])
- Alias whitelist (glob syntax, overrides blacklist)
- FCU connection URL.
- MAVLink protocol version. Supported: "v1.0", "v2.0" New in 0.18
- GCS bridge connection URL.
gcs_bridge
Additional proxy. Old name ros_udp.Subscribed Topics
mavlink/from (mavros_msgs/Mavlink)- Mavlink stream from autopilot.
Published Topics
mavlink/to (mavros_msgs/Mavlink)- Mavlink stream to autopilot.
Parameters
~gcs_url (string, default: udp:https://@)- Connection URL.
event_launcher
Listens to arming status, triggers and run programs on event. Example config.Subscribed Topics
mavros/state (mavros_msgs/State)- Source of arming events.
Services
<trigger_event> (std_srvs/Trigger)- Optional event triggers. You may create several services using configuration.
Parameters
~<event_name>/service (string)- Create event (with name <event_name>) triggered by service (param value).
- List of events triggered that handler.
- List of actions to do on corresponding event. Supported actions: run, stop.
- Command to run/stop on event.
- File to save stdout and stderr output of command. Optional.
Usage
Example launch files are in the mavros/launch directory. If the autopilot is on the PX4 native stack use the following to launch an example configuration:
roslaunch mavros px4.launch
If the autopilot is on the ArduPilot/APM stack firmware use the following:
roslaunch mavros apm.launch
Example configurations for the various mavros plugins can also be found in similarly named yaml files. For more details on the choices between APM and PX4 stacks checkout the pixhawk wiki.
Hardware notes:
- APM2.5/2.6 always APM stack
- Pixhawk from manufacturer usually comes with APM stack
- Pixhawk may be flashed by PX4 firmware using QGC or by upload make target.
If you unsure what firmware your FCU runs start apm.launch and see diagnostics. Starting from 0.11 mavros knows string representation for autopilot mavlink enum. For older you shall manually find autopilot type value in mavlink documentation.
Connection URL
Connection defined by URL, you can use any supported type for FCU and GCS.
Supported schemas:
Serial: /path/to/serial/device[:baudrate]
Serial: serial:https:///path/to/serial/device[:baudrate][/?ids=sysid,compid]
Serial with hardware flow control: serial-hwfc:https:///path/to/serial/device[:baudrate][?ids=sysid,compid]
UDP: udp:https://[bind_host][:port]@[remote_host][:port][/?ids=sysid,compid]
UDP Broadcast: udp-b:https://[bind_host][:port]@[:port][/?ids=sysid,compid]
TCP client: tcp:https://[server_host][:port][/?ids=sysid,compid]
TCP server: tcp-l:https://[bind_host][:port][/?ids=sysid,compid]
Notes:
ids from URL overrides ids given by parameters ~system_id and ~component_id.
baudrate default value is 57600
bind_host default value is "0.0.0.0" (IPv4 ANY)
remote_host by default unknown. mavros will awaiting data at bind_host:port
server_host default value is "localhost"
port default values: 14555 for UDP bind, 14550 for UDP remote, 5760 for TCP
- UDP broadcast used on discovery stage, later it switch to GCS address
- Currently supports only IPv4.
Utility commands
All utilities provides <util> --help and <util> <command> --help information.
mavcmd
usage: mavcmd [-h] [-n MAVROS_NS] [-v] [--wait] {long,int,sethome,takeoff,land,takeoffcur,landcur,trigger_control} ... Commad line tool for sending commands to MAVLink device. positional arguments: {long,int,sethome,takeoff,land,takeoffcur,landcur,trigger_control} long Send any command (COMMAND_LONG) int Send any command (COMMAND_INT) sethome Request change home position takeoff Request takeoff land Request land takeoffcur Request takeoff from current GPS coordinates landcur Request land on current GPS coordinates trigger_control Control onboard camera trigerring system (PX4) optional arguments: -h, --help show this help message and exit -n MAVROS_NS, --mavros-ns MAVROS_NS ROS node namespace -v, --verbose verbose output --wait Wait for establishing FCU connection
mavftp
PX4 only.
usage: mavftp [-h] [-n MAVROS_NS] [-v] {cd,list,cat,remove,mkdir,rmdir,download,upload,verify,reset} ... File manipulation tool for MAVLink-FTP. positional arguments: {cd,list,cat,remove,mkdir,rmdir,download,upload,verify,reset} cd change directory list list files and dirs cat cat file remove remove file mkdir create direcotory rmdir remove directory download download file upload upload file verify verify files reset reset optional arguments: -h, --help show this help message and exit -n MAVROS_NS, --mavros-ns MAVROS_NS ROS node namespace -v, --verbose verbose output
mavparam
usage: mavparam [-h] [-n MAVROS_NS] [-v] {load,dump,get,set} ... Commad line tool for getting, setting, parameters from MAVLink device. positional arguments: {load,dump,get,set} load load parameters from file dump dump parameters to file get get parameter set set parameter optional arguments: -h, --help show this help message and exit -n MAVROS_NS, --mavros-ns MAVROS_NS ROS node namespace -v, --verbose verbose output
mavsafety
usage: mavsafety [-h] [-n MAVROS_NS] [-v] {arm,disarm,safetyarea} ... Commad line tool for manipulating safty on MAVLink device. positional arguments: {arm,disarm,safetyarea} arm Arm motors disarm Disarm motors safetyarea Send safety area optional arguments: -h, --help show this help message and exit -n MAVROS_NS, --mavros-ns MAVROS_NS ROS node namespace -v, --verbose verbose output
mavsetp
Testing utility for setpoint plugins.
usage: mavsetp [-h] [-n MAVROS_NS] [-V] {local} ... Commad line tool for control the device by setpoints. positional arguments: {local} local Send local setpoint optional arguments: -h, --help show this help message and exit -n MAVROS_NS, --mavros-ns MAVROS_NS ROS node namespace -V, --verbose verbose output
mavsys
usage: mavsys [-h] [-n MAVROS_NS] [-v] [--wait] {mode,rate} ... Change mode and rate on MAVLink device. positional arguments: {mode,rate} mode Set mode rate Set stream rate optional arguments: -h, --help show this help message and exit -n MAVROS_NS, --mavros-ns MAVROS_NS ROS node namespace -v, --verbose verbose output --wait Wait for establishing FCU connection
Supported custom modes listed at mavros/CustomModes.
mavwp
usage: mavwp [-h] [-n MAVROS_NS] [-v] {show,load,pull,dump,clear,setcur,goto} ... Commad line tool for manipulating mission on MAVLink device. positional arguments: {show,load,pull,dump,clear,setcur,goto} show Show waypoints load load waypoints from file pull pull waypoints from FCU dump dump waypoints to file clear clear waypoints on device setcur set current waypoints on device goto send goto waypoint (APM only) optional arguments: -h, --help show this help message and exit -n MAVROS_NS, --mavros-ns MAVROS_NS ROS node namespace -v, --verbose verbose output
Plugins
Standard set of communication plugins loaded by mavros_node.
Note: this list for 0.18.0 version. Older versions: 0.6.0, 0.7.0, 0.8.0, 0.10.0, 0.11.0, 0.12.0 — 0.15.0, 0.16.0 — 0.17.0.
3dr_radio
Publish 3DR Radio status to diagnostics and topic.Published Topics
~radio_status (mavros_msgs/RadioStatus)- Status received from modem, same as RADIO_STATUS message.
actuator_control
Sends acruator commands to FCU.Subscribed Topics
~actuator_control (mavros_msgs/ActuatorControl)- actuator command
hil_controls
Publish HIL_CONTROLS New in 0.18Published Topics
~hil_controls/hil_controls (mavros_msgs/HilControls)- HIL data
Parameters
~frame_id (string, default: "map")- frame for altitude messages
command
Send COMMAND_LONG to FCU.Services
~cmd/command (mavros_msgs/CommandLong)- Send any COMMAND_LONG to FCU.
- Send any COMMAND_INT to FCU.
- Change Arming status.
- Change HOME location.
- Send takeoff command.
- Send land command.
- Send camera trigger control command.
Parameters
~cmd/use_comp_id_system_control (bool, default: false)- Use SYSTEM_CONTROL component id instead of mavros target component.
ftp
Support plugin for MAVLink-FTP (PX4).Services
~ftp/open (mavros_msgs/FileOpen)- Open file (acquire session).
- Close file (release session).
- Read from opened file.
- Write to opened file.
- List directory.
- Truncate file.
- Unlink file.
- Rename file/directory.
- Create directory.
- Remove directory.
- Request to calculate CRC32 of file on FCU.
- Reset FCU server (dangerous).
global_position
Publish global position information fused by FCU and raw GPS data.Published Topics
~global_position/global (sensor_msgs/NavSatFix)- GPS Fix. IMPORTANT: Altitude is specified as ellipsoid height and care must be taken to avoid a common pitfall. See this section for more.
- UTM coords.
- Velocity fused by FCU.
- Relative altitude.
- Compass heading in degrees.
- GPS position fix reported by the device.
- Velocity output from the GPS device.
Parameters
~global_position/frame_id (string, default: fcu)- frame_id for messages.
- Send or not local UTM coords via TF?
- frame_id for TF.
- Child frame_id for TF.
imu_pub
Publish IMU statePublished Topics
~imu/data (sensor_msgs/Imu)- Imu data, orientation computed by FCU
- Raw IMU data without orientation
- FCU compass data
- Temperature reported by FCU (usually from barometer)
- Air pressure.
Parameters
~imu/frame_id (string, default: fcu)- Frame ID for this plugin.
- Gyro's standard deviation
- Accel's standard deviation
- Standard deviation for IMU.orientation
- Standard deviation for magnetic field message (undefined if: 0.0)
local_position
Publish LOCAL_POSITION_NED in TF and PoseStamped topic.Published Topics
~local_position/pose (geometry_msgs/PoseStamped)- Local position from FCU.
- Velocity data from FCU.
Parameters
~local_position/frame_id (string, default: fcu)- frame_id for message.
- TF send switch.
- Origin frame_id for TF.
- Child frame_id for TF.
manual_control
Publish MANUAL_CONTROL message (user input).Subscribed Topics
~manual_control/send (mavros_msgs/ManualControl)- RC Rx, interpreted and normalized.
Published Topics
~manual_control/control (mavros_msgs/ManualControl)- RC Rx, interpreted and normalized.
param
Allows to access to FCU parameters and map it to ROS parameters in ~param/.Services
~param/pull (mavros_msgs/ParamPull)- Request parameter from device (or internal cache).
- Request send parameters from ROS to FCU.
- Return FCU parameter value.
- Set parameter on FCU immidiatly.
rc_io
Publish RC receiver inputs.Subscribed Topics
~rc/override (mavros_msgs/OverrideRCIn)- Send RC override message to FCU. APM and PX4 only. APM requires setup FCU param SYSID_MYGCS to match mavros system id. Not recommended to use in automatic control because lack of safety mechanisms. Use one of setpoint plugins and OFFBOARD mode.
Published Topics
~rc/in (mavros_msgs/RCIn)- Publish RC inputs (in raw milliseconds)
- Publish FCU servo outputs
safety_area
Sends safety allowed area to FCU. Initial area can be loaded from parameters.Subscribed Topics
~safety_area/set (geometry_msgs/PolygonStamped)- Volumetric area described by two corners.
Parameters
~safety_area/p1/x (double)- Corner 1 X.
- Corner 1 Y.
- Corner 1 Z.
- Corner 2 X.
- Corner 2 Y.
- Corner 2 Z.
setpoint_accel
Send acceleration setpoint.Subscribed Topics
~setpoint_accel/accel (geometry_msgs/Vector3Stamped)- Acceleration or force setpoint vector.
Parameters
~setpoint_accel/send_force (bool)- Send force setpoint.
setpoint_attitude
Send attitude setpoint using SET_ATTITUDE_TARGET.Subscribed Topics
~setpoint_attitude/cmd_vel (geometry_msgs/TwistStamped)- Send angular velocity.
- Send attitude setpoint.
- Send throttle value(0~1).
Parameters
~setpoint_attitude/reverse_throttle (bool, default: false)- Allow to send -1.0 throttle or not.
- Enable ~setpoint_attitude/target_attitude PoseStamped topic subscriber and disable ~setpoint_attitude/cmd_vel Twist topic.
- TF listen switch. Disable topics if enabled.
- Origin frame_id for TF.
- Child frame_id for TF.
- Rate limit for TF listener [Hz].
setpoint_position
Sends position setpoint using SET_POSITION_TARGET_GLOBAL_INT or SET_POSITION_TARGET_LOCAL_NED.Subscribed Topics
~setpoint_position/global (geographic_msgs/GeoPoseStamped)- Global frame setpoint position. Sends an LLA to the flight controller. Only YAW axis extracted from orientation field. IMPORTANT: Altitude is interpreted as AMSL and care must be taken to avoid a common pitfall. See this section for more.
- Local frame setpoint position. Only YAW axis extracted from orientation field.
- The old implementation of ~setpoint_position/global. Converts LLA to local ENU. This was done as a workaround before the flight controller could accept LLA setpoints directly. Consider using ~setpoint_position/global instead. See the details here. Only YAW axis extracted from orientation field.
Parameters
~setpoint_position/tf/listen (bool, default: false)- TF listen switch. Disable topic if enabled.
- Origin frame_id for TF.
- Child frame_id for TF.
- Rate limit for TF listener [Hz].
setpoint_raw
Send RAW setpoint messages to FCU and provide loopback topics (PX4).Subscribed Topics
~setpoint_raw/local (mavros_msgs/PositionTarget)- Local position, velocity and acceleration setpoint.
- Global position, velocity and acceleration setpoint.
- Attitude, angular rate and thrust setpoint.
Published Topics
~setpoint_raw/target_local (mavros_msgs/PositionTarget)- Local target loopback.
- Global target loopback.
- Attitude target loopback.
setpoint_velocity
Send velocity setpoint to FCU.Subscribed Topics
~setpoint_velocity/cmd_vel_unstamped (geometry_msgs/Twist)- Velocity setpoint.
sys_status
System status plugin. Handles FCU detection. REQUIRED never blacklist it!.Published Topics
~state (mavros_msgs/State)- FCU state
- FCU battery status report. DEPRECATED
- FCU battery status report. New in Kinetic
- Landing detector and VTOL state.
Services
~set_stream_rate (mavros_msgs/StreamRate)- Send stream rate request to FCU.
- Set FCU operation mode. See custom mode identifiers at modes page.
Parameters
~conn/timeout (double, default: 30.0)- Connection time out in seconds.
- Send HEARTBEAT message rate [Hz] (or disabled if 0.0)
- Minimal battery voltage for diagnostics.
- Disable all diag except HEARTBEAT message.
sys_time
System time plugin. Does time syncronization on PX4.Published Topics
~time_reference (sensor_msgs/TimeReference)- Time reference computed from SYSTEM_TIME.
Parameters
~conn/system_time_rate (double, default: 0.0)- Send SYSTEM_TIME to device rate [Hz] (disabled if 0.0).
- TIMESYNC rate. PX4 only.
- Ref source for time_reference message.
- Alpha for exponential moving average.
vfr_hud
Publish VFR_HUD and WIND messages.Published Topics
~vfr_hud (mavros_msgs/VFR_HUD)- Data for HUD.
- Wind estimation from FCU (APM).
waypoint
Allows to access to FCU mission (waypoints).Published Topics
~mission/reached (mavros_msgs/WaypointReached)- Publishes on reaching a waypoint from MISSION_ITEM_REACHED message.
- Current waypoint table. Updates on changes.
Services
~mission/pull (mavros_msgs/WaypointPull)- Request update waypoint list.
- Send new waypoint table.
- Clear mission on FCU.
- Set current seq. number in list.
Parameters
~mission/pull_after_gcs (bool, default: false)- Defines pull or not waypoints if detected GCS activity.
Notes
Plugins: `vision_position` and `vision_speed` moved to mavros_extras. New in 0.13 GPS and global_position plugins are merged. TF params moved to tf/ subnamespace. New in 0.16 Waypoint GOTO service removed. Please use setpoint plugins. New in 0.18 Experimental MAVLink 2.0 support (without packet signing).
Avoiding Pitfalls Related to Ellipsoid Height and Height Above Mean Sea Level
When controlling the FCU using global setpoints, you specify the altitude as meters above mean sea level (AMSL). But when sensing the global position, the altitude reported by ~global_position/global is specified as meters above the WGS-84 ellipsoid. This can lead to differences in altitude that are dozens of meters apart.
MAVROS uses GeographicLib to convert AMSL to ellipsoid height. When you install MAVROS using a package manager, this library gets installed as a dependency in Ubuntu.
To convert between AMSL and ellipsoid height, you add or subtract the geoid separation to the altitude. To go from AMSL to ellipsoid height, you add the value. And to go from ellipsoid height to AMSL you subtract the value. Consider these examples.
- Here is an example using python:
1 #!/usr/bin/env python3
2 # Example code that helps you convert between AMSL and ellipsoid height
3 # To run this code you need:
4 #
5 # 1) the egm96-5.pgm file from geographiclib.
6 # To get it on Ubuntu run:
7 # sudo apt install geographiclib-tools
8 # sudo geographiclib-get-geoids egm96-5
9 #
10 # 2) PyGeodesy
11 # To get it using pip:
12 # pip install PyGeodesy
13
14 from pygeodesy.geoids import GeoidPGM
15
16 _egm96 = GeoidPGM('/usr/share/GeographicLib/geoids/egm96-5.pgm', kind=-3)
17
18 def geoid_height(lat, lon):
19 """Calculates AMSL to ellipsoid conversion offset.
20 Uses EGM96 data with 5' grid and cubic interpolation.
21 The value returned can help you convert from meters
22 above mean sea level (AMSL) to meters above
23 the WGS84 ellipsoid.
24
25 If you want to go from AMSL to ellipsoid height, add the value.
26
27 To go from ellipsoid height to AMSL, subtract this value.
28 """
29 return _egm96.height(lat, lon)
In general, the ellipsoid height is better for calculations and AMSL is better for user interfaces. If you're calculating the distance between LLA positions, you most likely want to specify both altitudes in terms of height above the ellipsoid. Both representations have their uses.
For background information regarding ellipsoid height and AMSL, see this video: