mavlink : module documentation

MAVLink protocol implementation (auto-generated by mavgen.py)

Generated from: common.xml

Note: this file has been auto-generated. DO NOT EDIT
Function x25crc x25 CRC - based on checksum.h from mavlink library
Class MAVLink_header MAVLink message header
Class MAVLink_message base MAVLink message class
Class MAVLink_heartbeat_message The heartbeat message shows that a system is present and responding.
Class MAVLink_boot_message The boot message indicates that a system is starting. The onboard
Class MAVLink_system_time_message The system time is the time of the master clock, typically the
Class MAVLink_ping_message A ping message either requesting or responding to a ping. This allows
Class MAVLink_system_time_utc_message UTC date and time from GPS module
Class MAVLink_change_operator_control_message Request to control this MAV
Class MAVLink_change_operator_control_ack_message Accept / deny control of this MAV
Class MAVLink_auth_key_message Emit an encrypted signature / key identifying this system. PLEASE
Class MAVLink_action_ack_message This message acknowledges an action. IMPORTANT: The acknowledgement
Class MAVLink_action_message An action message allows to execute a certain onboard action. These
Class MAVLink_set_mode_message Set the system mode, as defined by enum MAV_MODE in
Class MAVLink_set_nav_mode_message Set the system navigation mode, as defined by enum MAV_NAV_MODE in
Class MAVLink_param_request_read_message Request to read the onboard parameter with the param_id string id.
Class MAVLink_param_request_list_message Request all parameters of this component. After his request, all
Class MAVLink_param_value_message Emit the value of a onboard parameter. The inclusion of param_count
Class MAVLink_param_set_message Set a parameter value TEMPORARILY to RAM. It will be reset to default
Class MAVLink_gps_raw_int_message The global position, as returned by the Global Positioning System
Class MAVLink_scaled_imu_message The RAW IMU readings for the usual 9DOF sensor setup. This message
Class MAVLink_gps_status_message The positioning status, as reported by GPS. This message is intended
Class MAVLink_raw_imu_message The RAW IMU readings for the usual 9DOF sensor setup. This message
Class MAVLink_raw_pressure_message The RAW pressure readings for the typical setup of one absolute
Class MAVLink_scaled_pressure_message The pressure readings for the typical setup of one absolute and
Class MAVLink_attitude_message The attitude in the aeronautical frame (right-handed, Z-down,
Class MAVLink_local_position_message The filtered local position (e.g. fused computer vision and
Class MAVLink_global_position_message The filtered global position (e.g. fused GPS and accelerometers).
Class MAVLink_gps_raw_message The global position, as returned by the Global Positioning System
Class MAVLink_sys_status_message The general system state. If the system is following the MAVLink
Class MAVLink_rc_channels_raw_message The RAW values of the RC channels received. The standard PPM
Class MAVLink_rc_channels_scaled_message The scaled values of the RC channels received. (-100%) -10000, (0%)
Class MAVLink_servo_output_raw_message The RAW values of the servo outputs (for RC input from the remote,
Class MAVLink_waypoint_message Message encoding a waypoint. This message is emitted to announce
Class MAVLink_waypoint_request_message Request the information of the waypoint with the sequence number seq.
Class MAVLink_waypoint_set_current_message Set the waypoint with sequence number seq as current waypoint. This
Class MAVLink_waypoint_current_message Message that announces the sequence number of the current active
Class MAVLink_waypoint_request_list_message Request the overall list of waypoints from the system/component.
Class MAVLink_waypoint_count_message This message is emitted as response to WAYPOINT_REQUEST_LIST by the
Class MAVLink_waypoint_clear_all_message Delete all waypoints at once.
Class MAVLink_waypoint_reached_message A certain waypoint has been reached. The system will either hold this
Class MAVLink_waypoint_ack_message Ack message during waypoint handling. The type field states if this
Class MAVLink_gps_set_global_origin_message As local waypoints exist, the global waypoint reference allows to
Class MAVLink_gps_local_origin_set_message Once the MAV sets a new GPS-Local correspondence, this message
Class MAVLink_local_position_setpoint_set_message Set the setpoint for a local position controller. This is the
Class MAVLink_local_position_setpoint_message Transmit the current local setpoint of the controller to other MAVs
Class MAVLink_control_status_message Undocumented
Class MAVLink_safety_set_allowed_area_message Set a safety zone (volume), which is defined by two corners of a
Class MAVLink_safety_allowed_area_message Read out the safety zone the MAV currently assumes.
Class MAVLink_set_roll_pitch_yaw_thrust_message Set roll, pitch and yaw.
Class MAVLink_set_roll_pitch_yaw_speed_thrust_message Set roll, pitch and yaw.
Class MAVLink_roll_pitch_yaw_thrust_setpoint_message Setpoint in roll, pitch, yaw currently active on the system.
Class MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message Setpoint in rollspeed, pitchspeed, yawspeed currently active on the
Class MAVLink_nav_controller_output_message Outputs of the APM navigation controller. The primary use of this
Class MAVLink_position_target_message The goal position of the system. This position is the input to any
Class MAVLink_state_correction_message Corrects the systems state by adding an error correction term to the
Class MAVLink_set_altitude_message Undocumented
Class MAVLink_request_data_stream_message Undocumented
Class MAVLink_hil_state_message This packet is useful for high throughput
Class MAVLink_hil_controls_message Hardware in the loop control outputs
Class MAVLink_manual_control_message Undocumented
Class MAVLink_rc_channels_override_message The RAW values of the RC channels sent to the MAV to override info
Class MAVLink_global_position_int_message The filtered global position (e.g. fused GPS and accelerometers). The
Class MAVLink_vfr_hud_message Metrics typically displayed on a HUD for fixed wing aircraft
Class MAVLink_command_message Send a command with up to four parameters to the MAV
Class MAVLink_command_ack_message Report status of a command. Includes feedback wether the command was
Class MAVLink_optical_flow_message Optical flow from a flow sensor (e.g. optical mouse sensor)
Class MAVLink_debug_vect_message Undocumented
Class MAVLink_named_value_float_message Send a key-value pair as float. The use of this message is
Class MAVLink_named_value_int_message Send a key-value pair as integer. The use of this message is
Class MAVLink_statustext_message Status text message. These messages are printed in yellow in the COMM
Class MAVLink_debug_message Send a debug value. The index is used to discriminate between values.
Class MAVError MAVLink error class
Class MAVString NUL terminated string
Class MAVLink_bad_data a piece of bad data in a mavlink stream
Class MAVLink MAVLink protocol handling class
def x25crc(buf):
x25 CRC - based on checksum.h from mavlink library
API Documentation for PyMAVLink, generated by pydoctor at 2011-08-20 08:50:37.