mav_msgs

Summary

mav_msgs
Version:

3.0.0

Description:

Package containing messages for communicating with rotary wing MAVs

Maintainers:
  • Fadri Furrer <fadri DOT furrer AT mavt DOT ethz DOT ch>
Licenses:
  • ASL 2.0
Urls:
Authors:
  • Simon Lynen
  • Markus Achtelik
  • Pascal Gohl
  • Sammy Omari
  • Michael Burri
  • Fadri Furrer
BuildDepends:
BuildtoolDepends:
 
BuildExportDepends:
 
ExecDepends:

Types

Message types

mav_msgs/RateThrust
Field:
Header header

# We use the coordinate frames with the following convention:
#   x: forward
#   y: left
#   z: up

geometry_msgs/Vector3 angular_rates  # Roll-, pitch-, yaw-rate around body axes [rad/s]
geometry_msgs/Vector3 thrust         # Thrust [N] expressed in the body frame.
                                     # For a fixed-wing, usually the x-component is used.
                                     # For a multi-rotor, usually the z-component is used.
                                     # Set all un-used components to 0.
mav_msgs/RollPitchYawrateThrust
Field:
Header header

# We use the coordinate frames with the following convention:
#   x: forward
#   y: left
#   z: up

# rotation convention (z-y'-x''):
# yaw rotates around fixed frame's z axis
# pitch rotates around new y-axis (y')
# roll rotates around new x-axis (x'')

# This is a convenience-message to support that low-level (microcontroller-based) state
# estimators may not have knowledge about the absolute yaw.
# Roll- and pitch-angle should be specified in the header/frame_id frame
float64 roll                   # Roll angle [rad]
float64 pitch                  # Pitch angle  [rad]
float64 yaw_rate               # Yaw rate around z-axis [rad/s]

geometry_msgs/Vector3 thrust   # Thrust [N] expressed in the body frame.
                               # For a fixed-wing, usually the x-component is used.
                               # For a multi-rotor, usually the z-component is used.
                               # Set all un-used components to 0.
mav_msgs/Actuators
Field:
  • header (std_msgs/Header) –
  • angles[] (float64) –
  • angular_velocities[] (float64) –
  • normalized[] (float64) –
Header header

# This message defines lowest level commands to be sent to the actuator(s). 

float64[] angles             # Angle of the actuator in [rad]. 
                             # E.g. servo angle of a control surface(not angle of the surface!), orientation-angle of a thruster.      
float64[] angular_velocities # Angular velocities of the actuator in [rad/s].
                             # E.g. "rpm" of rotors, propellers, thrusters 
float64[] normalized         # Everything that does not fit the above, normalized between [-1 ... 1].
mav_msgs/Status
Field:
  • header (std_msgs/Header) –
  • vehicle_name (string) –
  • vehicle_type (string) –
  • battery_voltage (float32) –
  • rc_command_mode (string) –
  • command_interface_enabled (bool) –
  • flight_time (float32) –
  • system_uptime (float32) –
  • cpu_load (float32) –
  • motor_status (string) –
  • gps_status (string) –
  • gps_num_satellites (int32) –
Constant:
  • RC_COMMAND_ATTITUDE (string):"attitude_thrust"
  • RC_COMMAND_ATTITUDE_HEIGHT (string):"attitude_height"
  • RC_COMMAND_POSITION (string):"position"
  • MOTOR_STATUS_RUNNING (string):"running"
  • MOTOR_STATUS_STOPPED (string):"stopped"
  • MOTOR_STATUS_STARTING (string):"starting"
  • MOTOR_STATUS_STOPPING (string):"stopping"
  • GPS_STATUS_LOCK (string):"lock"
  • GPS_STATUS_NO_LOCK (string):"no_lock"
Header header

# If values are not known / available, set to -1 or empty string. 
string      vehicle_name
string      vehicle_type                  # E.g. firefly, pelican ...
float32     battery_voltage               # Battery voltage in V.
string      rc_command_mode               # Command mode set on the 3 position switch on the rc.         
bool        command_interface_enabled     # Reports whether the serial command interface is enabled.
float32     flight_time                   # Flight time in s.
float32     system_uptime									# MAV uptime in s.
float32     cpu_load                      # MAV CPU load: 0.0 ... 1.0

string      motor_status                  # Current motor status: running, stopped, starting, stopping.

string      gps_status                    # GPS status: lock, no_lock
int32       gps_num_satellites            # Number of visible satellites

string RC_COMMAND_ATTITUDE="attitude_thrust"
string RC_COMMAND_ATTITUDE_HEIGHT="attitude_height"
string RC_COMMAND_POSITION="position"

string MOTOR_STATUS_RUNNING="running"
string MOTOR_STATUS_STOPPED="stopped"
string MOTOR_STATUS_STARTING="starting"
string MOTOR_STATUS_STOPPING="stopping"

string GPS_STATUS_LOCK="lock"
string GPS_STATUS_NO_LOCK="no_lock"
mav_msgs/TorqueThrust
Field:
Header header

# We use the coordinate frames with the following convention:
#   x: forward
#   y: left
#   z: up

geometry_msgs/Vector3 torque  # Torque expressed in the body frame [Nm].
geometry_msgs/Vector3 thrust  # Thrust [N] expressed in the body frame. 
                              # For a fixed-wing, usually the x-component is used.
                              # For a multi-rotor, usually the z-component is used. 
                              # Set all un-used components to 0.  
mav_msgs/AttitudeThrust
Field:
Header header

geometry_msgs/Quaternion attitude    # Attitude expressed in the header/frame_id frame.
geometry_msgs/Vector3 thrust         # Thrust [N] expressed in the body frame.
                                     # For a fixed-wing, usually the x-component is used.
                                     # For a multi-rotor, usually the z-component is used.
                                     # Set all un-used components to 0.