#pragma once
#include <cmath>
#include <stdarg.h>
#include <stdio.h>
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
#include <AP_AHRS/AP_AHRS.h>
#include <Filter/Filter.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_Scheduler/AP_Scheduler.h>
#include <AP_NavEKF2/AP_NavEKF2.h>
#include <AP_NavEKF3/AP_NavEKF3.h>
#include <SRV_Channel/SRV_Channel.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_Mission/AP_Mission.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
#include "config.h"
#include "defines.h"
#include "RC_Channel_Tracker.h"
#include "Parameters.h"
#include "GCS_MAVLink_Tracker.h"
#include "GCS_Tracker.h"
#include "AP_Arming_Tracker.h"
#include "mode.h"
class Tracker : public AP_Vehicle {
public:
friend class GCS_MAVLINK_Tracker;
friend class GCS_Tracker;
friend class Parameters;
friend class ModeAuto;
friend class ModeGuided;
friend class Mode;
void arm_servos();
void disarm_servos();
private:
Parameters g;
uint32_t start_time_ms = 0;
RC_Channels_Tracker rc_channels;
SRV_Channels servo_channels;
LowPassFilterFloat yaw_servo_out_filt;
LowPassFilterFloat pitch_servo_out_filt;
bool yaw_servo_out_filt_init = false;
bool pitch_servo_out_filt_init = false;
GCS_Tracker _gcs;
GCS_Tracker &gcs() { return _gcs; }
AP_BattMonitor battery{MASK_LOG_CURRENT,
FUNCTOR_BIND_MEMBER(&Tracker::handle_battery_failsafe, void, const char*, const int8_t),
nullptr};
Location current_loc;
Mode *mode_from_mode_num(enum Mode::Number num);
Mode *mode = &mode_initialising;
ModeAuto mode_auto;
ModeInitialising mode_initialising;
ModeManual mode_manual;
ModeGuided mode_guided;
ModeScan mode_scan;
ModeServoTest mode_servotest;
ModeStop mode_stop;
struct {
bool location_valid;
Location location;
Location location_estimate;
uint32_t last_update_us;
uint32_t last_update_ms;
Vector3f vel;
int32_t relative_alt;
} vehicle;
struct NavStatus {
float bearing;
float distance;
float pitch;
float angle_error_pitch;
float angle_error_yaw;
float alt_difference_baro;
float alt_difference_gps;
float altitude_offset;
bool manual_control_yaw : 1;
bool manual_control_pitch : 1;
bool need_altitude_calibration : 1;
bool scan_reverse_pitch : 1;
bool scan_reverse_yaw : 1;
} nav_status;
AP_Param param_loader{var_info};
bool target_set = false;
bool stationary = true;
static const AP_Scheduler::Task scheduler_tasks[];
static const AP_Param::Info var_info[];
static const struct LogStructure log_structure[];
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
uint8_t &task_count,
uint32_t &log_bit) override;
void one_second_loop();
void ten_hz_logging_loop();
void stats_update();
void send_nav_controller_output(mavlink_channel_t chan);
#if HAL_LOGGING_ENABLED
const AP_Int32 &get_log_bitmask() override { return g.log_bitmask; }
const struct LogStructure *get_log_structures() const override {
return log_structure;
}
uint8_t get_num_log_structures() const override;
void Log_Write_Attitude();
void Log_Write_Vehicle_Baro(float pressure, float altitude);
void Log_Write_Vehicle_Pos(int32_t lat,int32_t lng,int32_t alt, const Vector3f& vel);
void Log_Write_Vehicle_Startup_Messages();
#endif
void load_parameters(void) override;
void read_radio();
void update_ahrs();
void update_compass(void);
void update_GPS(void);
void handle_battery_failsafe(const char* type_str, const int8_t action);
void init_servos();
void update_pitch_servo(float pitch);
void update_pitch_position_servo(void);
void update_pitch_onoff_servo(float pitch) const;
void update_pitch_cr_servo(float pitch);
void update_yaw_servo(float yaw);
void update_yaw_position_servo(void);
void update_yaw_onoff_servo(float yaw) const;
void update_yaw_cr_servo(float yaw);
void init_ardupilot() override;
bool get_home_eeprom(Location &loc) const;
bool set_home_eeprom(const Location &temp) WARN_IF_UNUSED;
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
bool set_home(const Location &temp, bool lock) override WARN_IF_UNUSED;
void prepare_servos();
void set_mode(Mode &newmode, ModeReason reason);
bool set_mode(uint8_t new_mode, ModeReason reason) override;
uint8_t get_mode() const override { return (uint8_t)mode->number(); }
bool should_log(uint32_t mask);
bool start_command_callback(const AP_Mission::Mission_Command& cmd) { return false; }
void exit_mission_callback() { return; }
bool verify_command_callback(const AP_Mission::Mission_Command& cmd) { return false; }
void update_vehicle_pos_estimate();
void update_tracker_position();
void update_bearing_and_distance();
void update_tracking(void);
void tracking_update_position(const mavlink_global_position_int_t &msg);
void tracking_update_pressure(const mavlink_scaled_pressure_t &msg);
void tracking_manual_control(const mavlink_manual_control_t &msg);
void update_armed_disarmed() const;
bool get_pan_tilt_norm(float &pan_norm, float &tilt_norm) const override;
AP_Arming_Tracker arming;
AP_Mission mission{
FUNCTOR_BIND_MEMBER(&Tracker::start_command_callback, bool, const AP_Mission::Mission_Command &),
FUNCTOR_BIND_MEMBER(&Tracker::verify_command_callback, bool, const AP_Mission::Mission_Command &),
FUNCTOR_BIND_MEMBER(&Tracker::exit_mission_callback, void)};
};
extern Tracker tracker;