Plugins for mavros 0.11

Standard plugin set for mavros version 0.11.

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.

actuator_control

Sends acruator commands to FCU. New in 0.11.0

Subscribed Topics

~actuator_control (mavros/ActuatorControl)
  • actuator command

command

Send COMMAND_LONG to FCU.

Services

~cmd/command (mavros/CommandLong)
  • Send any COMMAND_LONG to FCU.
~cmd/command_int (mavros/CommandInt)
  • Send any COMMAND_INT to FCU.
~cmd/arming (mavros/CommandBool)
  • Change Arming status.
~cmd/set_home (mavros/CommandHome)
  • Change HOME location.
~cmd/guided_enable (mavros/CommandBool)
  • Enable guided mode by sending MAV_CMD_NAV_GUIDED_ENABLE command.
~cmd/takeoff (mavros/CommandTOL)
  • Send takeoff command.
~cmd/land (mavros/CommandTOL)
  • Send land 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/FileOpen)
  • Open file (acquire session).
~ftp/close (mavros/FileClose)
  • Close file (release session).
~ftp/read (mavros/FileRead)
  • Read from opened file.
~ftp/write (mavros/FileWrite)
  • Write to opened file.
~ftp/list (mavros/FileList)
  • List directory.
~ftp/truncate (mavros/FileTruncate)
  • Truncate file.
~ftp/remove (mavros/FileRemove)
  • Unlink file.
~ftp/rename (mavros/FileRename)
  • Rename file/directory.
~ftp/mkdir (mavros/FileMakeDir)
  • Create directory.
~ftp/rmdir (mavros/FileRemoveDir)
  • Remove directory.
~ftp/checksum (mavros/FileChecksum)
  • Request to calculate CRC32 of file on FCU.
~ftp/reset (std_srvs/Empty)
  • Reset FCU server (dangerous).

global_position

Publish global position information fused by FCU.

Published Topics

~global_position/global (sensor_msgs/NavSatFix)
  • GPS Fix.
~global_position/local (geometry_msgs/PoseWithCovarianceStamped)
  • UTM coords.
~global_position/gp_vel (geometry_msgs/Vector3Stamped)
  • Velocity fused by FCU.
~global_position/rel_alt (std_msgs/Float64)
  • Relative altitude.
~global_position/compass_hdg (std_msgs/Float64)
  • Compass heading in degrees.

Parameters

~global_position/send_tf (bool)
  • Send or not local UTM coords?
~global_position/frame_id (string, default: local_origin)
  • Origin frame_id for TF.
~global_position/child_frame_id (string, default: fcu)
  • Child frame_id for TF.

gps

Publish GPS Fix (like nmea_navsat_driver)

Published Topics

~gps/fix (sensor_msgs/NavSatFix)
  • GPS position fix reported by the device.
~gps/gps_vel (geometry_msgs/TwistStamped)
  • Velocity output from the GPS device.

Parameters

~gps/frame_id (string, default: gps)
  • Frame ID for fix message.

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 (, default: 0.0)
  • 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/local (geometry_msgs/PoseStamped)
  • Local position from FCU.

Parameters

~local_position/send_tf (bool, default: true)
  • TF send switch.
~local_position/frame_id (string, default: local_origin)
  • Origin frame_id for TF.
~local_position/child_frame_id (string, default: fcu)

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).
~param/push (mavros/ParamPush)
  • Request send parameters from ROS to FCU.
~param/get (mavros/ParamGet)
  • Return FCU parameter value.
~param/set (mavros/ParamSet)
  • Set parameter on FCU immidiatly.

rc_io

Publish RC receiver inputs.

Published Topics

~rc/in (mavros/RCIn)
  • Publish RC inputs (in raw milliseconds)
~rc/out (mavros/RCOut)
  • Publish FCU servo outputs
~rc/override (mavros/OverrideRCIn)
  • Send RC override message to FCU. APM only. Requires setup FCU param SYSID_MYGCS to match mavros system id.

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.

setpoint_accel

Send acceleration setpoint to FCU.

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_EXTERNAL to FCU.

Subscribed Topics

~setpoint_attitude/cmd_vel (geometry_msgs/TwistStamped)
  • Send angular velocity.
~setpoint_attitude/attitude (geometry_msgs/PoseStamped)
  • Send attitude setpoint.
~setpoint_attitude/attitude (geometry_msgs/PoseWithCovarianceStamped)
  • Send attitude setpoint with covariance (alternative).

Parameters

~setpoint_attitude/listen_tf (bool, default: false)
  • TF listen switch. Disable topics if enabled.
~setpoint_attitude/listen_twist (bool, default: false)
  • Use att_vel topic instead of attitude.
~setpoint_attutude/pose_with_covariance (bool, default: false)
  • Selector for attitude message type.
~setpoint_attutude/frame_id (string, default: local_origin)
  • Origin frame_id for TF.
~setpoint_attitude/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].

setpoint_position

Sent LOCAL_NED_POSITION_SETPOINT_EXTERNAL to FCU.

Subscribed Topics

~setpoint_position/local (geometry_msgs/PoseStamped)
  • Setpoint position. Orientation not used.

Parameters

~setpoint_position/listen_tf (bool, default: false)
  • TF listen switch. Disable topic if enabled.
~setpoint_position/frame_id (string, default: local_origin)
  • Origin frame_id for TF.
~setpoint_position/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].

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/State)
  • FCU state
~battery (mavros/BatteryStatus)
  • FCU battery status report.

Services

~set_stream_rate (mavros/StreamRate)
  • Send stream rate request to FCU.
~set_mode (mavros/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 (double, default: 0.0)
  • Period to send HEARTBEAT messages (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.

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.
~conn/timesync (double, default: 0.0)
  • TIMESYNC period. 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.

vfr_hud

Publish VFR_HUD and WIND messages.

Published Topics

~vfr_hud (mavros/VFR_HUD)
  • Data for HUD.
~wind_estimation (geometry_msgs/TwistStamped)
  • Wind estimation from FCU (APM).

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.
~mission/push (mavros/WaypointPush)
  • Send new waypoint table.
~mission/clear (mavros/WaypointClear)
  • Clear mission on FCU.
~mission/set_current (mavros/WaypointSetCurrent)
  • Set current seq. number in list.
~mission/goto (mavros/WaypointGOTO)
  • Send goto point (APM specific).

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.

Wiki: mavros/Plugins_0.11 (last edited 2015-08-01 10:17:18 by vooon)