Contents
Plugins for mavros 0.10
Standard plugin set for mavros version 0.10.
sys_status
System status plugin. Handles FCU detection.Published Topics
~state (mavros/State)- FCU state
- FCU battery status report.
Services
~set_stream_rate (mavros/StreamRate)- Send stream rate request to FCU. (Since 0.5.0)
- Set FCU operation mode. See custom mode identifiers at modes page. New in 0.8.0
Parameters
~conn_timeout (double, default: 30.0)- Connection time out in seconds.
- Period to send HEARTBEAT messages (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 (double, default: 0.0)- Send SYSTEM_TIME to device period in seconds.
- TIMESYNC period. PX4 only.
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)
gps
Publish GPS Fix (like nmea_navsat_driver)Published Topics
~fix (sensor_msgs/NavSatFix)- GPS position fix reported by the device.
- Velocity output from the GPS device.
Parameters
~gps/frame_id (string, default: gps)- Frame ID for fix message.
- Ref source for time_reference message.
param
Allows to access to FCU parameters and map it to ROS parameters in ~param/.Services
~param/pull (mavros/ParamPull)- Request parameter from device (or internal cache).
- Request send parameters from ROS to FCU.
- Return FCU parameter value.
- Set parameter on FCU immidiatly.
waypoint
Allows to access to FCU mission (waypoints).Published Topics
~mission/waypoints (mavros/WaypointList)- Current waypoint table. Updates on changes.
Services
~mission/pull (mavros/WaypointPull)- Request update waypoint list.
- Send new waypoint table.
- Clear mission on FCU.
- Set current seq. number in list.
- Send goto point (APM specific).
Parameters
~mission/pull_after_gcs (bool, default: false)- Defines pull or not waypoints if detected GCS activity.
rc_io
Publish RC receiver inputs.Published Topics
~rc/in (mavros/RCIn)- Publish RC inputs (in raw milliseconds)
- Publish FCU servo outputs
- Send RC override message to FCU. APM only. Requires setup FCU param SYSID_MYGCS to match mavros system id.
command
Send COMMAND_LONG to FCU.Services
~cmd/command (mavros/CommandLong)- Send any COMMAND_LONG to FCU.
- Send any COMMAND_INT to FCU.
- Change Arming status.
- Change HOME location.
- Enable guided mode by sending MAV_CMD_NAV_GUIDED_ENABLE command.
- Send takeoff command.
- Send land command.
Parameters
~cmd/use_comp_id_system_control (bool, default: false)- Use SYSTEM_CONTROL component id instead of mavros target component.
local_position
Publish LOCAL_POSITION_NED in TF and PoseStamped topic.Published Topics
~position/local (geometry_msgs/PoseStamped)- Local position from FCU.
Parameters
~position/local/send_tf (bool, default: true)- TF send switch.
- Origin frame_id for TF.
- Child frame_id for TF and PoseStamped.
setpoint_accel
Send acceleration setpoint to FCU.Subscribed Topics
~setpoint/accel (geometry_msgs/Vector3)- Acceleration or force setpoint vector.
Parameters
~setpoint/accel/send_force (bool)- Send force setpoint.
setpoint_attitude
Send ATTITUDE_SETPOINT_EXTERNAL to FCU.Subscribed Topics
~setpoint/att_vel (geometry_msgs/Twist)- Send angular velocity.
- Send attitude setpoint.
- Send attitude setpoint with covariance (alternative).
Parameters
~setpoint/attitude/listen_tf (bool, default: false)- TF listen switch. Disable topics if enabled.
- Use att_vel topic instead of attitude.
- Selector for attitude message type.
- Origin frame_id for TF.
- Child frame_id for TF.
- Rate limit for TF listener [Hz].
setpoint_position
Sent LOCAL_NED_POSITION_SETPOINT_EXTERNAL to FCU.Subscribed Topics
~setpoint/local_setpoint (geometry_msgs/PoseStamped)- Setpoint position. Orientation not used.
Parameters
~setpoint/position/listen_tf (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_velocity
Send velocity setpoint to FCU.Subscribed Topics
~setpoint/cmd_vel (geometry_msgs/Twist)- Velocity setpoint.
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.
3dr_radio
Publish 3DR Radio status to diagnostics and topic.Published Topics
~radio_status (mavros/RadioStatus)- Status received from modem, same as RADIO_STATUS message.
vfr_hud
Publish VFR_HUD and WIND messages. New in 0.8.0Published Topics
~vfr_hud (mavros/VFR_HUD)- Data for HUD.
- Wind estimation from FCU (APM).
global_position
Publish global position information fused by FCU. New in 0.8.0Published Topics
~global_position/global (sensor_msgs/NavSatFix)- GPS Fix.
- UTM coords.
- Velocity fused by FCU.
- Relative altitude.
- Compass heading in degrees.
Parameters
~global_position/send_tf (bool)- Send or not local UTM coords?
- Origin frame_id for TF.
- Child frame_id for TF.
ftp
Support plugin for MAVLink-FTP (PX4). New in 0.8.0Services
~ftp/open (mavros/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).
Notes
Setpoint plugins are mutually exclusive, please blacklist all unused plugins. Also APM does not support this commands.
Also blacklist 3dr_radio if you dont use 3DR Radio for FCU connection.
Plugins: `vision_position` and `vision_speed` moved to mavros_extras.