Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/AntennaTracker/Tracker.h
Views: 1798
/*1Lead developers: Matthew Ridley and Andrew Tridgell23Please contribute your ideas! See https://ardupilot.org/dev for details45This program is free software: you can redistribute it and/or modify6it under the terms of the GNU General Public License as published by7the Free Software Foundation, either version 3 of the License, or8(at your option) any later version.910This program is distributed in the hope that it will be useful,11but WITHOUT ANY WARRANTY; without even the implied warranty of12MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the13GNU General Public License for more details.1415You should have received a copy of the GNU General Public License16along with this program. If not, see <http://www.gnu.org/licenses/>.17*/18#pragma once1920////////////////////////////////////////////////////////////////////////////////21// Header includes22////////////////////////////////////////////////////////////////////////////////2324#include <cmath>25#include <stdarg.h>26#include <stdio.h>2728#include <AP_Common/AP_Common.h>29#include <AP_Param/AP_Param.h>30#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library31#include <AP_AHRS/AP_AHRS.h> // ArduPilot Mega DCM Library32#include <Filter/Filter.h> // Filter library3334#include <AP_Logger/AP_Logger.h>35#include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler36#include <AP_NavEKF2/AP_NavEKF2.h>37#include <AP_NavEKF3/AP_NavEKF3.h>3839#include <SRV_Channel/SRV_Channel.h>40#include <AP_Vehicle/AP_Vehicle.h>41#include <AP_Mission/AP_Mission.h>42#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library4344// Configuration45#include "config.h"46#include "defines.h"4748#include "RC_Channel_Tracker.h"49#include "Parameters.h"50#include "GCS_MAVLink_Tracker.h"51#include "GCS_Tracker.h"5253#include "AP_Arming.h"5455#include "mode.h"5657class Tracker : public AP_Vehicle {58public:59friend class GCS_MAVLINK_Tracker;60friend class GCS_Tracker;61friend class Parameters;62friend class ModeAuto;63friend class ModeGuided;64friend class Mode;6566void arm_servos();67void disarm_servos();6869private:70Parameters g;7172uint32_t start_time_ms = 0;7374/**75antenna control channels76*/77RC_Channels_Tracker rc_channels;78SRV_Channels servo_channels;7980LowPassFilterFloat yaw_servo_out_filt;81LowPassFilterFloat pitch_servo_out_filt;8283bool yaw_servo_out_filt_init = false;84bool pitch_servo_out_filt_init = false;8586GCS_Tracker _gcs; // avoid using this; use gcs()87GCS_Tracker &gcs() { return _gcs; }8889// Battery Sensors90AP_BattMonitor battery{MASK_LOG_CURRENT,91FUNCTOR_BIND_MEMBER(&Tracker::handle_battery_failsafe, void, const char*, const int8_t),92nullptr};93Location current_loc;9495Mode *mode_from_mode_num(enum Mode::Number num);9697Mode *mode = &mode_initialising;9899ModeAuto mode_auto;100ModeInitialising mode_initialising;101ModeManual mode_manual;102ModeGuided mode_guided;103ModeScan mode_scan;104ModeServoTest mode_servotest;105ModeStop mode_stop;106107// Vehicle state108struct {109bool location_valid; // true if we have a valid location for the vehicle110Location location; // lat, long in degrees * 10^7; alt in meters * 100111Location location_estimate; // lat, long in degrees * 10^7; alt in meters * 100112uint32_t last_update_us; // last position update in microseconds113uint32_t last_update_ms; // last position update in milliseconds114Vector3f vel; // the vehicle's velocity in m/s115int32_t relative_alt; // the vehicle's relative altitude in meters * 100116} vehicle;117118// Navigation controller state119struct NavStatus {120float bearing; // bearing to vehicle in centi-degrees121float distance; // distance to vehicle in meters122float pitch; // pitch to vehicle in degrees (positive means vehicle is above tracker, negative means below)123float angle_error_pitch; // angle error between target and current pitch in centi-degrees124float angle_error_yaw; // angle error between target and current yaw in centi-degrees125float alt_difference_baro; // altitude difference between tracker and vehicle in meters according to the barometer. positive value means vehicle is above tracker126float alt_difference_gps; // altitude difference between tracker and vehicle in meters according to the gps. positive value means vehicle is above tracker127float altitude_offset; // offset in meters which is added to tracker altitude to align altitude measurements with vehicle's barometer128bool manual_control_yaw : 1;// true if tracker yaw is under manual control129bool manual_control_pitch : 1;// true if tracker pitch is manually controlled130bool need_altitude_calibration : 1;// true if tracker altitude has not been determined (true after startup)131bool scan_reverse_pitch : 1;// controls direction of pitch movement in SCAN mode132bool scan_reverse_yaw : 1;// controls direction of yaw movement in SCAN mode133} nav_status;134135// setup the var_info table136AP_Param param_loader{var_info};137138bool target_set = false;139bool stationary = true; // are we using the start lat and log?140141static const AP_Scheduler::Task scheduler_tasks[];142static const AP_Param::Info var_info[];143static const struct LogStructure log_structure[];144145// Tracker.cpp146void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,147uint8_t &task_count,148uint32_t &log_bit) override;149void one_second_loop();150void ten_hz_logging_loop();151void stats_update();152153// GCS_Mavlink.cpp154void send_nav_controller_output(mavlink_channel_t chan);155156#if HAL_LOGGING_ENABLED157// methods for AP_Vehicle:158const AP_Int32 &get_log_bitmask() override { return g.log_bitmask; }159const struct LogStructure *get_log_structures() const override {160return log_structure;161}162uint8_t get_num_log_structures() const override;163164// Log.cpp165void Log_Write_Attitude();166void Log_Write_Vehicle_Baro(float pressure, float altitude);167void Log_Write_Vehicle_Pos(int32_t lat,int32_t lng,int32_t alt, const Vector3f& vel);168void Log_Write_Vehicle_Startup_Messages();169#endif170171// Parameters.cpp172void load_parameters(void) override;173174// radio.cpp175void read_radio();176177// sensors.cpp178void update_ahrs();179void compass_save();180void update_compass(void);181void update_GPS(void);182void handle_battery_failsafe(const char* type_str, const int8_t action);183184// servos.cpp185void init_servos();186void update_pitch_servo(float pitch);187void update_pitch_position_servo(void);188void update_pitch_onoff_servo(float pitch) const;189void update_pitch_cr_servo(float pitch);190void update_yaw_servo(float yaw);191void update_yaw_position_servo(void);192void update_yaw_onoff_servo(float yaw) const;193void update_yaw_cr_servo(float yaw);194195// system.cpp196void init_ardupilot() override;197bool get_home_eeprom(Location &loc) const;198bool set_home_eeprom(const Location &temp) WARN_IF_UNUSED;199bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;200bool set_home(const Location &temp, bool lock) override WARN_IF_UNUSED;201void prepare_servos();202void set_mode(Mode &newmode, ModeReason reason);203bool set_mode(uint8_t new_mode, ModeReason reason) override;204uint8_t get_mode() const override { return (uint8_t)mode->number(); }205bool should_log(uint32_t mask);206bool start_command_callback(const AP_Mission::Mission_Command& cmd) { return false; }207void exit_mission_callback() { return; }208bool verify_command_callback(const AP_Mission::Mission_Command& cmd) { return false; }209210// tracking.cpp211void update_vehicle_pos_estimate();212void update_tracker_position();213void update_bearing_and_distance();214void update_tracking(void);215void tracking_update_position(const mavlink_global_position_int_t &msg);216void tracking_update_pressure(const mavlink_scaled_pressure_t &msg);217void tracking_manual_control(const mavlink_manual_control_t &msg);218void update_armed_disarmed() const;219bool get_pan_tilt_norm(float &pan_norm, float &tilt_norm) const override;220221// Arming/Disarming management class222AP_Arming_Tracker arming;223224// Mission library225AP_Mission mission{226FUNCTOR_BIND_MEMBER(&Tracker::start_command_callback, bool, const AP_Mission::Mission_Command &),227FUNCTOR_BIND_MEMBER(&Tracker::verify_command_callback, bool, const AP_Mission::Mission_Command &),228FUNCTOR_BIND_MEMBER(&Tracker::exit_mission_callback, void)};229};230231extern Tracker tracker;232233234