Show EOL distros: 

rosflight_pkgs: rosflight | rosflight_firmware | rosflight_msgs | rosflight_sim | rosflight_utils

Package Summary

Package for interfacing to the ROSflight autopilot firmware over MAVLink

rosflight_pkgs: rosflight | rosflight_firmware | rosflight_msgs | rosflight_sim | rosflight_utils

Package Summary

Package for interfacing to the ROSflight autopilot firmware over MAVLink

rosflight_pkgs: rosflight | rosflight_firmware | rosflight_msgs | rosflight_sim | rosflight_utils

Package Summary

Package for interfacing to the ROSflight autopilot firmware over MAVLink

Overview

ROSflight provides a simple, low-latency interface between a flight controller running the ROSflight firmware and ROS. ROSflight can stream both sensor data and motor commands at high speed. ROSflight is written to work with a variety of airframes, including multirotor and fixed-wing aircraft. The ROSflight package provided the interface for autopilots, but does not include any control code. For examples of autopilots using ROSflight, see ROSPlane or ROSCopter. For documentation on the firmware, see https://docs.rosflight.org.

Sample Usage

The following command will run the node that interfaces the autopilot with ROS running on the onboard computer (this must be run on a computer that is physically connected to the autopilot via USB or serial):

$ rosrun rosflight rosflight_io _port:=/dev/ttyUSB0

Nodes

rosflight_io

Interfaces between ROS on the onboard computer and the ROSflight firmware on the autopilot. Streams sensor data to the onboard computer and control and configuration commands to the autopilot. Sensor stream topics are only advertised if they are being transmitted by the autopilot.

Subscribed Topics

command (rosflight_msgs/Command)
  • Control setpoint to send to the autopilot. The interpretation of the setpoint values depends on the value of the mode field. Which setpoint values to listen to can be controlled by setting the bits of the ignore field.
aux_command (rosflight_msgs/AuxCommand)
  • Auxiliary command for the flight controller. This sets motors and/or servos that are not used by the mixer for flight. The type_array selects outputs and indicates whether they are motors or servos, and the values array sets the output value of the motor/servo.
external_attitude (geometry_msgs/Quaternion)
  • Corrected value for the internal estimator. Use this if you have an external sensor providing better estimates of the current attitude of the aircraft than the onboard estimator, such as a motion capture system. In between external_attitude messages, the estimator continues running to keep the estimate current. For fixed-wing aircraft, the internal estimator is only used for the attitude topic.

Published Topics

airspeed (rosflight_msgs/Airspeed)
  • Airspeed (meters/second) and differential pressure measurement (Pascals) from a differential pressure sensor, if attached.
attitude (rosflight_msgs/Attitude)
  • Attitude estimate from the autopilot, including orientation and angular velocity in the body frame with NED axes.
attitude/euler (geometry_msgs/Vector3Stamped)
  • Attitude estimate from the autopilot as Euler angles, in the NED frame
baro (rosflight_msgs/Barometer)
  • Barometer measurement, including pressure (Pascals), temperature (Kelvin), and computed altitude (meters). Computed altitude is relative to where the barometer was calibrated.
battery (rosflight_msgs/BatteryMonitor)
  • Current battery status, including voltage (Volts) and current (Amps), if a battery monitor is present
gnss (rosflight_msgs/GNSS)
  • Information from a GNSS receiver connected directly to the flight contoller. For more details, see the message definition. Not available in version 1.3 and earlier.
gnss_full (rosflight_msgs/GNSSFull)
  • The complete GNSS position, velocity, and time message from the receiver. This topic is intended for debugging, but may contain useful information. Some fields have strange units; see the message definition for details. Not available in version 1.3 and earlier.
imu/data (sensor_msgs/Imu)
  • Inertial measurement unit (IMU) data (3-axis accelerometer, 3-axis gyro) in the body frame with NED axes.
imu/temperature (sensor_msgs/Temperature)
  • Temperature from the IMU's internal sensor, in Degrees Celsius
magnetometer (sensor_msgs/MagneticField)
  • 3-axis magnetometer data in the NED frame, in Tesla
navsat_compat/fix (sensor_msgs/NavSatFix)
  • GNSS information from the attached GNSS receiver. This is intended to duplicate the API provided by the nmea_navsat_driver package. Not currently functional.
navsat_compat/time_reference (sensor_msgs/TimeReference)
  • Provides the current GNSS time from the attached GNSS receiver. This is intended to duplicate the API provided by the nmea_navsat_driver package. The header contains the ROS time when the time was valid, and the time field contains GNSS time. Not currently functional.
navsat_compat/vel (geometry_msgs/TwistStamped)
  • Velocity measurement from the attached GNSS receiver. Only the linear field is filled. This is intended to duplicate the API provided by the nmea_navsat_driver package. Not currently functional.
output_raw (rosflight_msgs/OutputRaw)
  • Raw motor/servo outputs from the autopilot
rc_raw (rosflight_msgs/RCRaw)
  • Raw RC inputs to the autopilot from the RC receiver
rosflight_errors (rosflight_msgs/Error)
  • Major error messages from the firmware. This topic is only used for errors that crash the firmware, which are very unlikely in unmodified firmware. In event of a firmware crash, the firmware will restart and publish a message to this topic. There is some logic that attempts to prevent the aircraft from crashing (i.e. into the ground) in such a situation. See the firmware documentation
sonar (sensor_msgs/Range)
  • Distance measurement from an ultrasonic rangefinder, if attached
status (rosflight_msgs/Status)
  • Status of the autopilot, including armed state, failsafe state, and error states
unsaved_params (std_msgs/Bool)
  • Whether there are parameters that have been set on the autopilot but not saved to non-volatile memory
version (std_msgs/String)
  • String describing the firmware version running on the autopilot
named_value/int/<name> (std_msgs/Int32)
  • Raw named integer value sent from autopilot (used for debugging purposes)
named_value/float/<name> (std_msgs/Float32)
  • Raw named floating point value sent from autopilot (used for debugging purposes)

Services

param_get (rosflight_msgs/ParamGet) param_set (rosflight_msgs/ParamSet) param_write (std_srvs/Trigger)
  • Writes all autopilot parameters to non-volatile memory
param_save_to_file (rosflight_msgs/ParamFile)
  • Saves all current autopilot parameters to specified file on onboard computer
param_load_from_file (rosflight_msgs/ParamFile)
  • Sets values of autopilot parameters to those saved in the specified file on the onboard computer
calibrate_imu (std_srvs/Trigger)
  • Starts an IMU calibration. IMU calibration will fail if the flight controller is not level or moves. Calibration errors are indicated through rosout, not from the service response.
calibrate_rc_trim (std_srvs/Trigger)
  • Sets the equilibrium feed-forward commands to those specified by the current RC trim setpoints. After calibrating, set RC trims back to zero. Does not work while the aircraft is armed.
calibrate_baro (std_srvs/Trigger)
  • Calibrates the barometer, setting the current altitude to 0. Calibration fails if the aircraft is moved during calibration.
calibrate_airspeed (std_srvs/Trigger)
  • Calibrates the airspeed sensor, setting the current airspeed to 0. To prevent errors, shield the airspeed sensor from wind during calibration. Calibration fails if the aircraft is moved during calibration.
reboot (std_srvs/Trigger)
  • Reboots the autopilot. Does nothing while armed.
reboot_to_bootloader (std_srvs/Trigger)
  • Reboots the autopilot to the bootloader for flashing firmware. Does nothing while armed. May not work on all flight controllers.

Parameters

~port (string, default: /dev/ttyACM0)
  • Serial port to which the autopilot is connected
~baud_rate (int, default: 921600)
  • Baud rate for the autopilot serial connection
~frame_id (string, default: world)
  • The frame in which sensor data will be returned
~udp (bool, default: false)
  • If true, use UDP instead of UART serial. Used for Gazebo software-in-the-loop simulator.
~bind_host (string, default: localhost)
  • UDP bind host name
~bind_port (int, default: 14520)
  • UDP bind port
~remote_host (string, default: value of bind_host parameter)
  • UDP remote host name
~remote_port (int, default: 14525)
  • UDP remote port

Wiki: rosflight (last edited 2020-05-07 19:00:10 by TreyHenrichsen)