플러그인(Plugins)
1. 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.
2. actuator_control
Sends acruator commands to FCU.
Subscribed Topics
~actuator_control (mavros_msgs/ActuatorControl)
actuator command
3. hil_controls
Publish HIL_CONTROLS New in 0.18
Published Topics
~hil_controls/hil_controls (mavros_msgs/HilControls)
HIL data
Parameters
~frame_id (string, default: "map")
frame for altitude messages
4. command
Send COMMAND_LONG to FCU.
Services
~cmd/command (mavros_msgs/CommandLong)
Send any COMMAND_LONG to FCU.
~cmd/command_int (mavros_msgs/CommandInt)
Send any COMMAND_INT to FCU.
~cmd/arming (mavros_msgs/CommandBool)
Change Arming status.
~cmd/set_home (mavros_msgs/CommandHome)
Change HOME location.
~cmd/takeoff (mavros_msgs/CommandTOL)
Send takeoff command.
~cmd/land (mavros_msgs/CommandTOL)
Send land command.
~cmd/trigger_control (mavros_msgs/CommandTriggerControl)
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.
5. ftp
Support plugin for MAVLink-FTP (PX4).
Services
~ftp/open (mavros_msgs/FileOpen)
Open file (acquire session).
~ftp/close (mavros_msgs/FileClose)
Close file (release session).
~ftp/read (mavros_msgs/FileRead)
Read from opened file.
~ftp/write (mavros_msgs/FileWrite)
Write to opened file.
~ftp/list (mavros_msgs/FileList)
List directory.
~ftp/truncate (mavros_msgs/FileTruncate)
Truncate file.
~ftp/remove (mavros_msgs/FileRemove)
Unlink file.
~ftp/rename (mavros_msgs/FileRename)
Rename file/directory.
~ftp/mkdir (mavros_msgs/FileMakeDir)
Create directory.
~ftp/rmdir (mavros_msgs/FileRemoveDir)
Remove directory.
~ftp/checksum (mavros_msgs/FileChecksum)
Request to calculate CRC32 of file on FCU.
~ftp/reset (std_srvs/Empty)
Reset FCU server (dangerous).
6. 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.
~global_position/local (geometry_msgs/PoseWithCovarianceStamped)
UTM coords.
~global_position/gp_vel (geometry_msgs/TwistStamped)
Velocity fused by FCU.
~global_position/rel_alt (std_msgs/Float64)
Relative altitude.
~global_position/compass_hdg (std_msgs/Float64)
Compass heading in degrees.
~global_position/raw/fix (sensor_msgs/NavSatFix)
GPS position fix reported by the device.
~global_position/raw/gps_vel (geometry_msgs/TwistStamped)
Velocity output from the GPS device.
Parameters
~global_position/frame_id (string, default: fcu)
frame_id for messages.
~global_position/tf/send (bool, default: true)
Send or not local UTM coords via TF?
~global_position/tf/frame_id (string, default: local_origin)
frame_id for TF.
~global_position/tf/child_frame_id (string, default: fcu_utm)
Child frame_id for TF.
7. imu_pub
Publish IMU state
Published Topics
~imu/data (sensor_msgs/Imu)
Imu data, orientation computed by FCU
~imu/data_raw (sensor_msgs/Imu)
Raw IMU data without orientation
~imu/mag (sensor_msgs/MagneticField)
FCU compass data
~imu/temperature (sensor_msgs/Temperature)
Temperature reported by FCU (usually from barometer)
~imu/atm_pressure (sensor_msgs/FluidPressure)
Air pressure.
Parameters
~imu/frame_id (string, default: fcu)
Frame ID for this plugin.
~imu/linear_acceleration_stdev (double, default: 0.0003)
Gyro's standard deviation
~imu/angular_velocity_stdev (double, default: !dec 0.02)
Accel's standard deviation
~imu/orientation_stdev (double, default: 1.0)
Standard deviation for IMU.orientation
~imu/magnetic_stdev (double, default: 0.0)
Standard deviation for magnetic field message (undefined if: 0.0)
8. local_position
Publish LOCAL_POSITION_NED in TF and PoseStamped topic.
Published Topics
~local_position/pose (geometry_msgs/PoseStamped)
Local position from FCU.
~local_position/velocity (geometry_msgs/TwistStamped)
Velocity data from FCU.
Parameters
~local_position/frame_id (string, default: fcu)
frame_id for message.
~local_position/tf/send (bool, default: true)
TF send switch.
~local_position/tf/frame_id (string, default: local_origin)
Origin frame_id for TF.
~local_position/tf/child_frame_id (string, default: fcu)
Child frame_id for TF.
9. 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.
10. 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).
~param/push (mavros_msgs/ParamPush)
Request send parameters from ROS to FCU.
~param/get (mavros_msgs/ParamGet)
Return FCU parameter value.
~param/set (mavros_msgs/ParamSet)
Set parameter on FCU immidiatly.
11. 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)
~rc/out (mavros_msgs/RCOut)
Publish FCU servo outputs
12. 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.
~safety_area/p1/y (double)
Corner 1 Y.
~safety_area/p1/z (double)
Corner 1 Z.
~safety_area/p2/x (double)
Corner 2 X.
~safety_area/p2/y (double)
Corner 2 Y.
~safety_area/p2/z (double)
Corner 2 Z.
13. 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.
14. setpoint_attitude
Send attitude setpoint using SET_ATTITUDE_TARGET.
Subscribed Topics
~setpoint_attitude/cmd_vel (geometry_msgs/TwistStamped)
Send angular velocity.
~setpoint_attitude/attitude (geometry_msgs/PoseStamped)
Send attitude setpoint.
~setpoint_attitude/thrust (mavros_msgs/Thrust)
Send throttle value(0~1).
Parameters
~setpoint_attitude/reverse_throttle (bool, default: false)
Allow to send -1.0 throttle or not.
~setpoint_attitude/use_quaternion (bool, default: false)
Enable ~setpoint_attitude/target_attitude PoseStamped topic subscriber and disable ~setpoint_attitude/cmd_vel Twist topic.
~setpoint_attitude/tf/listen (bool, default: false)
TF listen switch. Disable topics if enabled.
~setpoint_attutude/tf/frame_id (string, default: local_origin)
Origin frame_id for TF.
~setpoint_attitude/tf/child_frame_id (string, default: attitude)
Child frame_id for TF.
~setpoint_attitude/tf/rate_limit (double, default: 10.0)
Rate limit for TF listener [Hz].
15. 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.
~setpoint_position/local (geometry_msgs/PoseStamped)
Local frame setpoint position. Only YAW axis extracted from orientation field.
~setpoint_position/global_to_local (geographic_msgs/GeoPoseStamped)
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.
~setpoint_position/tf/frame_id (string, default: local_origin)
Origin frame_id for TF.
~setpoint_position/tf/child_frame_id (string, default: setpoint)
Child frame_id for TF.
~setpoint_position/tf/rate_limit (double, default: 50.0)
Rate limit for TF listener [Hz].
16. 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.
~setpoint_raw/global (mavros_msgs/GlobalPositionTarget)
Global position, velocity and acceleration setpoint.
~setpoint_raw/attitude (mavros_msgs/AttitudeTarget)
Attitude, angular rate and thrust setpoint.
Published Topics
~setpoint_raw/target_local (mavros_msgs/PositionTarget)
Local target loopback.
~setpoint_raw/target_global (mavros_msgs/GlobalPositionTarget)
Global target loopback.
~setpoint_raw/target_attitude (mavros_msgs/AttitudeTarget)
Attitude target loopback.
17. setpoint_velocity
Send velocity setpoint to FCU.
Subscribed Topics
~setpoint_velocity/cmd_vel_unstamped (geometry_msgs/Twist)
Velocity setpoint.
18. sys_status
System status plugin. Handles FCU detection. REQUIRED never blacklist it!.
Published Topics
~state (mavros_msgs/State)
FCU state
~battery (mavros_msgs/BatteryStatus)
FCU battery status report. DEPRECATED
~battery (sensor_msgs/BatteryState)
FCU battery status report. New in Kinetic
~extended_state (mavros_msgs/ExtendedState)
Landing detector and VTOL state.
Services
~set_stream_rate (mavros_msgs/StreamRate)
Send stream rate request to FCU.
~set_mode (mavros_msgs/SetMode)
Set FCU operation mode. See custom mode identifiers at modes page.
Parameters
~conn/timeout (double, default: 30.0)
Connection time out in seconds.
~conn/heartbeat_rate (double, default: 0.0)
Send HEARTBEAT message rate [Hz] (or disabled if 0.0)
~sys/min_voltage (double, default: 6.0)
Minimal battery voltage for diagnostics.
~sys/disable_diag (bool, default: false)
Disable all diag except HEARTBEAT message.
19. 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).
~conn/timesync_rate (double, default: 0.0)
TIMESYNC rate. PX4 only.
~time/time_ref_source (string, default: "fcu")
Ref source for time_reference message.
~time/timesync_avg_alpha (double, default: 0.6)
Alpha for exponential moving average.
20. vfr_hud
Publish VFR_HUD and WIND messages.
Published Topics
~vfr_hud (mavros_msgs/VFR_HUD)
Data for HUD.
~wind_estimation (geometry_msgs/TwistStamped)
Wind estimation from FCU (APM).
21. 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.
~mission/waypoints (mavros_msgs/WaypointList)
Current waypoint table. Updates on changes.
Services
~mission/pull (mavros_msgs/WaypointPull)
Request update waypoint list.
~mission/push (mavros_msgs/WaypointPush)
Send new waypoint table.
~mission/clear (mavros_msgs/WaypointClear)
Clear mission on FCU.
~mission/set_current (mavros_msgs/WaypointSetCurrent)
Set current seq. number in list.
Parameters
~mission/pull_after_gcs (bool, default: false)
Defines pull or not waypoints if detected GCS activity.
Last updated