플러그인(Plugins)
Last updated
Last updated
Publish 3DR Radio status to diagnostics and topic.
Published Topics
~radio_status ()
Status received from modem, same as RADIO_STATUS message.
Sends acruator commands to FCU.
Subscribed Topics
~actuator_control ()
actuator command
Publish HIL_CONTROLS New in 0.18
Published Topics
~hil_controls/hil_controls ()
HIL data
Parameters
~frame_id (string, default: "map")
frame for altitude messages
Send COMMAND_LONG to FCU.
Services
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.
Support plugin for MAVLink-FTP (PX4).
Services
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).
Publish global position information fused by FCU and raw GPS data.
Published Topics
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.
~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.
Publish IMU state
Published Topics
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.
~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)
Published Topics
Local position from FCU.
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.
Publish MANUAL_CONTROL message (user input).
Subscribed Topics
RC Rx, interpreted and normalized.
Published Topics
RC Rx, interpreted and normalized.
Allows to access to FCU parameters and map it to ROS parameters in ~param/.
Services
Request parameter from device (or internal cache).
Request send parameters from ROS to FCU.
Return FCU parameter value.
Set parameter on FCU immidiatly.
Publish RC receiver inputs.
Subscribed Topics
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
Publish RC inputs (in raw milliseconds)
Publish FCU servo outputs
Sends safety allowed area to FCU. Initial area can be loaded from parameters.
Subscribed Topics
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.
Send acceleration setpoint.
Subscribed Topics
Acceleration or force setpoint vector.
Parameters
~setpoint_accel/send_force (bool)
Send force setpoint.
Send attitude setpoint using SET_ATTITUDE_TARGET.
Subscribed Topics
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.
~setpoint_attitude/use_quaternion (bool, default: false)
~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].
Sends position setpoint using SET_POSITION_TARGET_GLOBAL_INT or SET_POSITION_TARGET_LOCAL_NED.
Subscribed Topics
Local frame setpoint position. 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].
Send RAW setpoint messages to FCU and provide loopback topics (PX4).
Subscribed Topics
Local position, velocity and acceleration setpoint.
Global position, velocity and acceleration setpoint.
Attitude, angular rate and thrust setpoint.
Published Topics
Local target loopback.
Global target loopback.
Attitude target loopback.
Send velocity setpoint to FCU.
Subscribed Topics
Velocity setpoint.
System status plugin. Handles FCU detection. REQUIRED never blacklist it!.
Published Topics
FCU state
FCU battery status report. DEPRECATED
FCU battery status report. New in Kinetic
Landing detector and VTOL state.
Services
Send stream rate request to FCU.
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.
System time plugin. Does time syncronization on PX4.
Published Topics
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.
Publish VFR_HUD and WIND messages.
Published Topics
Data for HUD.
Wind estimation from FCU (APM).
Allows to access to FCU mission (waypoints).
Published Topics
Publishes on reaching a waypoint from MISSION_ITEM_REACHED message.
Current waypoint table. Updates on changes.
Services
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.
~cmd/command ()
~cmd/command_int ()
~cmd/arming ()
~cmd/set_home ()
~cmd/takeoff ()
~cmd/land ()
~cmd/trigger_control ()
~ftp/open ()
~ftp/close ()
~ftp/read ()
~ftp/write ()
~ftp/list ()
~ftp/truncate ()
~ftp/remove ()
~ftp/rename ()
~ftp/mkdir ()
~ftp/rmdir ()
~ftp/checksum ()
~ftp/reset ()
~global_position/global ()
GPS Fix. IMPORTANT: Altitude is specified as ellipsoid height and care must be taken to avoid a common pitfall. .
~global_position/local ()
~global_position/gp_vel ()
~global_position/rel_alt ()
~global_position/compass_hdg ()
~global_position/raw/fix ()
~global_position/raw/gps_vel ()
~imu/data ()
~imu/data_raw ()
~imu/mag ()
~imu/temperature ()
~imu/atm_pressure ()
Publish LOCAL_POSITION_NED in and topic.
~local_position/pose ()
~local_position/velocity ()
~manual_control/send ()
~manual_control/control ()
~param/pull ()
~param/push ()
~param/get ()
~param/set ()
~rc/override ()
~rc/in ()
~rc/out ()
~safety_area/set ()
~setpoint_accel/accel ()
~setpoint_attitude/cmd_vel ()
~setpoint_attitude/attitude ()
~setpoint_attitude/thrust ()
Enable ~setpoint_attitude/target_attitude topic subscriber and disable ~setpoint_attitude/cmd_vel Twist topic.
~setpoint_position/global ()
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. .
~setpoint_position/local ()
~setpoint_position/global_to_local ()
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. . Only YAW axis extracted from orientation field.
~setpoint_raw/local ()
~setpoint_raw/global ()
~setpoint_raw/attitude ()
~setpoint_raw/target_local ()
~setpoint_raw/target_global ()
~setpoint_raw/target_attitude ()
~setpoint_velocity/cmd_vel_unstamped ()
~state ()
~battery ()
~battery ()
~extended_state ()
~set_stream_rate ()
~set_mode ()
Set FCU operation mode. See custom mode identifiers at .
~time_reference ()
~vfr_hud ()
~wind_estimation ()
~mission/reached ()
~mission/waypoints ()
~mission/pull ()
~mission/push ()
~mission/clear ()
~mission/set_current ()