Contents
Plugins for mavros 0.16-0.17
Standard plugin set for mavros version 0.16—0.17.
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.
altitude
Publish altitude information.Published Topics
~altitude (mavros_msgs/Altitude)- Direct copy of altitude data provided by Mavlink.
Parameters
~frame_id (string, default: "map")- frame for altitude messages
actuator_control
Sends acruator commands to FCU. New in 0.11.0Subscribed Topics
~actuator_control (mavros_msgs/ActuatorControl)- actuator command
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.
- 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). New in 0.15.0Published 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.
Parameters
~setpoint_attitude/reverse_throttle (bool, default: false)- Allow to send -1.0 throttle or not.
- 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
Sent position setpoint using SET_POSITION_TARGET_LOCAL_NED.Subscribed Topics
~setpoint_position/local (geometry_msgs/PoseStamped)- Setpoint position. 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 (geometry_msgs/TwistStamped)- 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.
- 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/waypoints (mavros_msgs/WaypointList)- 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.