APM:Libraries
Classes | Macros | Enumerations | Functions
GCS.h File Reference

Interface definition for the various Ground Control System. More...

#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include "GCS_MAVLink.h"
#include <DataFlash/DataFlash.h>
#include <AP_Mission/AP_Mission.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <stdint.h>
#include "MAVLink_routing.h"
#include <AP_SerialManager/AP_SerialManager.h>
#include <AP_Mount/AP_Mount.h>
#include <AP_Avoidance/AP_Avoidance.h>
#include <AP_Proximity/AP_Proximity.h>
#include <AP_HAL/utility/RingBuffer.h>
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
#include <AP_Camera/AP_Camera.h>
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>
#include <AP_VisualOdom/AP_VisualOdom.h>
#include <AP_Common/AP_FWVersion.h>
Include dependency graph for GCS.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  GCS_MAVLINK
 MAVLink transport control class. More...
 
struct  GCS_MAVLINK::stream_entries
 
struct  GCS_MAVLINK::pending_param_request
 
struct  GCS_MAVLINK::pending_param_reply
 
class  GCS
 global GCS object More...
 
struct  GCS::statustext_t
 

Macros

#define PAYLOAD_SIZE(chan, id)   (GCS_MAVLINK::packet_overhead_chan(chan)+MAVLINK_MSG_ID_ ## id ## _LEN)
 
#define HAVE_PAYLOAD_SPACE(chan, id)   (comm_get_txspace(chan) >= PAYLOAD_SIZE(chan, id))
 
#define CHECK_PAYLOAD_SIZE(id)   if (comm_get_txspace(chan) < packet_overhead()+MAVLINK_MSG_ID_ ## id ## _LEN) return false
 
#define CHECK_PAYLOAD_SIZE2(id)   if (!HAVE_PAYLOAD_SPACE(chan, id)) return false
 
#define MAV_STREAM_ENTRY(stream_name)
 
#define MAV_STREAM_TERMINATOR   { (streams)0, nullptr, 0 }
 

Enumerations

enum  ap_message : uint8_t {
  MSG_HEARTBEAT, MSG_ATTITUDE, MSG_LOCATION, MSG_EXTENDED_STATUS1,
  MSG_EXTENDED_STATUS2, MSG_NAV_CONTROLLER_OUTPUT, MSG_CURRENT_WAYPOINT, MSG_VFR_HUD,
  MSG_SERVO_OUTPUT_RAW, MSG_RADIO_IN, MSG_RAW_IMU1, MSG_RAW_IMU2,
  MSG_RAW_IMU3, MSG_GPS_RAW, MSG_GPS_RTK, MSG_GPS2_RAW,
  MSG_GPS2_RTK, MSG_SYSTEM_TIME, MSG_SERVO_OUT, MSG_NEXT_WAYPOINT,
  MSG_NEXT_PARAM, MSG_FENCE_STATUS, MSG_AHRS, MSG_SIMSTATE,
  MSG_HWSTATUS, MSG_WIND, MSG_RANGEFINDER, MSG_TERRAIN,
  MSG_BATTERY2, MSG_CAMERA_FEEDBACK, MSG_MOUNT_STATUS, MSG_OPTICAL_FLOW,
  MSG_GIMBAL_REPORT, MSG_MAG_CAL_PROGRESS, MSG_MAG_CAL_REPORT, MSG_EKF_STATUS_REPORT,
  MSG_LOCAL_POSITION, MSG_PID_TUNING, MSG_VIBRATION, MSG_RPM,
  MSG_MISSION_ITEM_REACHED, MSG_POSITION_TARGET_GLOBAL_INT, MSG_ADSB_VEHICLE, MSG_BATTERY_STATUS,
  MSG_AOA_SSA, MSG_LANDING, MSG_NAMED_FLOAT, MSG_LAST
}
 

Functions

GCSgcs ()
 

Detailed Description

Interface definition for the various Ground Control System.

Definition in file GCS.h.

Macro Definition Documentation

◆ CHECK_PAYLOAD_SIZE

#define CHECK_PAYLOAD_SIZE (   id)    if (comm_get_txspace(chan) < packet_overhead()+MAVLINK_MSG_ID_ ## id ## _LEN) return false

◆ CHECK_PAYLOAD_SIZE2

#define CHECK_PAYLOAD_SIZE2 (   id)    if (!HAVE_PAYLOAD_SPACE(chan, id)) return false

Definition at line 30 of file GCS.h.

Referenced by AP_Landing_Deepstall::send_deepstall_message().

◆ HAVE_PAYLOAD_SPACE

#define HAVE_PAYLOAD_SPACE (   chan,
  id 
)    (comm_get_txspace(chan) >= PAYLOAD_SIZE(chan, id))

◆ MAV_STREAM_ENTRY

#define MAV_STREAM_ENTRY (   stream_name)
Value:
{ \
GCS_MAVLINK::stream_name, \
stream_name ## _msgs, \
ARRAY_SIZE(stream_name ## _msgs) \
}

Definition at line 89 of file GCS.h.

◆ MAV_STREAM_TERMINATOR

#define MAV_STREAM_TERMINATOR   { (streams)0, nullptr, 0 }

Definition at line 95 of file GCS.h.

◆ PAYLOAD_SIZE

#define PAYLOAD_SIZE (   chan,
  id 
)    (GCS_MAVLINK::packet_overhead_chan(chan)+MAVLINK_MSG_ID_ ## id ## _LEN)

Enumeration Type Documentation

◆ ap_message

enum ap_message : uint8_t

NOTE: to ensure we never block on sending MAVLink messages please keep each MSG_ to a single MAVLink message. If need be create new MSG_ IDs for additional messages on the same stream

Enumerator
MSG_HEARTBEAT 
MSG_ATTITUDE 
MSG_LOCATION 
MSG_EXTENDED_STATUS1 
MSG_EXTENDED_STATUS2 
MSG_NAV_CONTROLLER_OUTPUT 
MSG_CURRENT_WAYPOINT 
MSG_VFR_HUD 
MSG_SERVO_OUTPUT_RAW 
MSG_RADIO_IN 
MSG_RAW_IMU1 
MSG_RAW_IMU2 
MSG_RAW_IMU3 
MSG_GPS_RAW 
MSG_GPS_RTK 
MSG_GPS2_RAW 
MSG_GPS2_RTK 
MSG_SYSTEM_TIME 
MSG_SERVO_OUT 
MSG_NEXT_WAYPOINT 
MSG_NEXT_PARAM 
MSG_FENCE_STATUS 
MSG_AHRS 
MSG_SIMSTATE 
MSG_HWSTATUS 
MSG_WIND 
MSG_RANGEFINDER 
MSG_TERRAIN 
MSG_BATTERY2 
MSG_CAMERA_FEEDBACK 
MSG_MOUNT_STATUS 
MSG_OPTICAL_FLOW 
MSG_GIMBAL_REPORT 
MSG_MAG_CAL_PROGRESS 
MSG_MAG_CAL_REPORT 
MSG_EKF_STATUS_REPORT 
MSG_LOCAL_POSITION 
MSG_PID_TUNING 
MSG_VIBRATION 
MSG_RPM 
MSG_MISSION_ITEM_REACHED 
MSG_POSITION_TARGET_GLOBAL_INT 
MSG_ADSB_VEHICLE 
MSG_BATTERY_STATUS 
MSG_AOA_SSA 
MSG_LANDING 
MSG_NAMED_FLOAT 
MSG_LAST 

Definition at line 37 of file GCS.h.

Function Documentation

◆ gcs()

GCS& gcs ( )

Definition at line 3172 of file GCS_Common.cpp.

Referenced by EEPROMClass::_ErasePage(), GCS_MAVLINK::_handle_command_preflight_calibration_baro(), AP_GPS_UBLOX::_parse_gps(), AP_GPS_UBLOX::_save_cfg(), AP_Motors::add_motor_num(), AP_Arming::airspeed_checks(), AP_AccelCal::AP_AccelCal(), AP_Arming::arm(), AP_Arming::arm_checks(), AP_Arming::barometer_checks(), AP_Arming::battery_checks(), AP_Arming::board_voltage_checks(), AP_GPS_SBF::broadcast_configuration_failure_reason(), AP_GPS_UBLOX::broadcast_configuration_failure_reason(), AP_GPS::broadcast_first_configuration_failure_reason(), AP_GPS_Backend::broadcast_gps_type(), AP_Landing_Deepstall::build_approach_path(), NavEKF2_core::calcGpsGoodToAlign(), NavEKF3_core::calcGpsGoodToAlign(), AP_Airspeed::calibrate(), AP_Baro::calibrate(), AP_AdvancedFailsafe::check(), AP_Tuning::check_controller_error(), SoaringController::check_cruise_criteria(), AP_BattMonitor::check_failsafes(), AP_Tuning::check_input(), AP_Tuning::check_selector_switch(), NavEKF2_core::checkAttitudeAlignmentStatus(), NavEKF3_core::checkAttitudeAlignmentStatus(), AP_Arming::compass_checks(), NavEKF2_core::controlMagYawReset(), NavEKF3_core::controlMagYawReset(), GCS_MAVLINK::data_stream_send(), AP_SmartRTL::deactivate(), AP_Arming::disarm(), AP_ICEngine::engine_control(), NavEKF3_core::FuseBodyVel(), NavEKF3_core::FuseOptFlow(), AP_AdvancedFailsafe::gcs_terminate(), AP_Arming::gps_checks(), AP_Follow::handle_msg(), AP_ADSB::handle_out_cfg(), GCS_MAVLINK::handle_timesync(), AP_ADSB::handle_transceiver_report(), AP_Arming::hardware_safety_check(), AP_MotorsTri::init(), AP_SmartRTL::init(), AP_Airspeed::init(), DataFlash_Class::Init(), AP_Frsky_Telem::init(), AP_InertialSensor::BatchSampler::init(), AP_Mission::init(), NavEKF3::InitialiseFilter(), NavEKF2::InitialiseFilter(), NavEKF3_core::InitialiseFilterBootstrap(), AP_Arming::ins_checks(), AP_Mission::jump_to_landing_sequence(), AP_Camera::log_picture(), AP_Arming::logging_checks(), AP_Arming::manual_transmitter_checks(), VRBRAIN::VRBRAINRCInput::new_input(), PX4::PX4RCInput::new_input(), AP_Tuning::next_parameter(), AP_Landing_Deepstall::override_servos(), AP_MotorsHeli::parameter_check(), AP_MotorsHeli_Single::parameter_check(), AP_Landing_Deepstall::predict_travel_distance(), AP_GPS_SBF::prepare_for_arming(), AP_GPS_SBF::process_message(), AP_Arming::rc_calibration_checks(), AP_Arming::rc_checks_copter_sub(), AP_Airspeed::read(), NavEKF2_core::readMagData(), NavEKF3_core::readMagData(), NavEKF2_core::realignYawGPS(), NavEKF3_core::realignYawGPS(), AP_Landing::restart_landing_sequence(), AP_Param::save(), AP_Param::send_parameter(), GCS_MAVLINK::send_text(), AP_BoardConfig::sensor_config_error(), AP_Arming::servo_checks(), NavEKF2_core::setAidingMode(), NavEKF3_core::setAidingMode(), NavEKF2_core::setOrigin(), NavEKF3_core::setOrigin(), NavEKF3_core::setup_core(), AP_Camera::setup_feedback_callback(), AP_AccelCal::start(), GCS_MAVLINK::try_send_message(), AP_Landing::type_slope_adjust_landing_slope_for_rangefinder_bump(), AP_Landing::type_slope_do_land(), AP_Landing::type_slope_setup_landing_glide_slope(), AP_Landing::type_slope_verify_land(), AP_ICEngine::update(), AP_ADSB::update(), AP_Airspeed::update_calibration(), AP::PerfInfo::update_logging(), AP_Landing_Deepstall::update_steering(), SoaringController::update_thermalling(), AP_Camera::update_trigger(), and AP_Landing::verify_land().

Here is the call graph for this function:
Here is the caller graph for this function: