2015-06-01 02:04:25 -03:00
/*
Lead developers : Matthew Ridley and Andrew Tridgell
2016-05-05 19:10:08 -03:00
2021-05-26 23:33:17 -03:00
Please contribute your ideas ! See https : //ardupilot.org/dev for details
2015-06-01 02:04:25 -03:00
This program is free software : you can redistribute it and / or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation , either version 3 of the License , or
( at your option ) any later version .
This program is distributed in the hope that it will be useful ,
but WITHOUT ANY WARRANTY ; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
GNU General Public License for more details .
You should have received a copy of the GNU General Public License
along with this program . If not , see < http : //www.gnu.org/licenses/>.
*/
2016-05-05 19:10:08 -03:00
# pragma once
2015-06-01 02:04:25 -03:00
////////////////////////////////////////////////////////////////////////////////
// Header includes
////////////////////////////////////////////////////////////////////////////////
2016-03-31 18:43:36 -03:00
# include <cmath>
2015-06-01 02:04:25 -03:00
# include <stdarg.h>
# include <stdio.h>
2015-08-11 03:28:40 -03:00
# include <AP_Common/AP_Common.h>
# include <AP_Param/AP_Param.h>
# include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
# include <AP_AHRS/AP_AHRS.h> // ArduPilot Mega DCM Library
# include <Filter/Filter.h> // Filter library
2019-01-18 00:23:42 -04:00
# include <AP_Logger/AP_Logger.h>
2015-08-11 03:28:40 -03:00
# include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler
2015-09-22 22:51:47 -03:00
# include <AP_NavEKF2/AP_NavEKF2.h>
2016-07-14 02:08:43 -03:00
# include <AP_NavEKF3/AP_NavEKF3.h>
2015-08-11 03:28:40 -03:00
2022-07-18 02:02:13 -03:00
# include <SRV_Channel/SRV_Channel.h>
2015-08-11 03:28:40 -03:00
# include <AP_Vehicle/AP_Vehicle.h>
# include <AP_Mission/AP_Mission.h>
2019-08-06 04:09:08 -03:00
# include <AP_Stats/AP_Stats.h> // statistics library
2015-08-11 03:28:40 -03:00
# include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
2015-06-01 02:04:25 -03:00
// Configuration
# include "config.h"
# include "defines.h"
2018-04-26 23:27:00 -03:00
# include "RC_Channel.h"
2015-06-01 02:04:25 -03:00
# include "Parameters.h"
2016-05-27 10:14:08 -03:00
# include "GCS_Mavlink.h"
2017-02-13 21:30:32 -04:00
# include "GCS_Tracker.h"
2015-08-11 03:28:40 -03:00
2020-02-18 19:29:10 -04:00
# include "AP_Arming.h"
2021-11-15 01:08:32 -04:00
# if AP_SCRIPTING_ENABLED
2019-03-01 02:40:18 -04:00
# include <AP_Scripting/AP_Scripting.h>
# endif
2019-09-13 12:41:55 -03:00
# include "mode.h"
2018-12-27 02:34:01 -04:00
class Tracker : public AP_Vehicle {
2015-06-01 02:04:25 -03:00
public :
2016-05-27 10:14:08 -03:00
friend class GCS_MAVLINK_Tracker ;
2017-02-13 21:30:32 -04:00
friend class GCS_Tracker ;
2015-06-01 02:04:25 -03:00
friend class Parameters ;
2019-09-13 12:41:55 -03:00
friend class ModeAuto ;
2019-09-25 06:55:59 -03:00
friend class ModeGuided ;
2019-09-13 12:41:55 -03:00
friend class Mode ;
2015-06-01 02:04:25 -03:00
Tracker ( void ) ;
2015-10-19 15:32:37 -03:00
2021-01-05 19:50:14 -04:00
void arm_servos ( ) ;
void disarm_servos ( ) ;
2015-06-01 02:04:25 -03:00
private :
Parameters g ;
2015-06-08 01:14:10 -03:00
uint32_t start_time_ms = 0 ;
2015-06-01 02:04:25 -03:00
2019-01-18 00:23:42 -04:00
AP_Logger logger ;
2015-12-27 03:05:14 -04:00
2015-06-01 02:04:25 -03:00
/**
antenna control channels
*/
2018-04-26 23:27:00 -03:00
RC_Channels_Tracker rc_channels ;
2017-01-06 22:51:56 -04:00
SRV_Channels servo_channels ;
2015-06-01 02:04:25 -03:00
2016-07-27 23:19:54 -03:00
LowPassFilterFloat yaw_servo_out_filt ;
LowPassFilterFloat pitch_servo_out_filt ;
bool yaw_servo_out_filt_init = false ;
bool pitch_servo_out_filt_init = false ;
2017-02-13 21:30:32 -04:00
GCS_Tracker _gcs ; // avoid using this; use gcs()
GCS_Tracker & gcs ( ) { return _gcs ; }
2015-06-01 02:04:25 -03:00
2019-08-06 04:09:08 -03:00
AP_Stats stats ;
2017-11-26 21:51:11 -04:00
// Battery Sensors
2018-03-01 23:38:30 -04:00
AP_BattMonitor battery { MASK_LOG_CURRENT ,
FUNCTOR_BIND_MEMBER ( & Tracker : : handle_battery_failsafe , void , const char * , const int8_t ) ,
nullptr } ;
2015-06-01 02:04:25 -03:00
struct Location current_loc ;
2019-09-13 12:41:55 -03:00
Mode * mode_from_mode_num ( enum Mode : : Number num ) ;
Mode * mode = & mode_initialising ;
ModeAuto mode_auto ;
ModeInitialising mode_initialising ;
ModeManual mode_manual ;
2019-09-25 06:55:59 -03:00
ModeGuided mode_guided ;
2019-09-13 12:41:55 -03:00
ModeScan mode_scan ;
ModeServoTest mode_servotest ;
ModeStop mode_stop ;
2015-06-01 02:04:25 -03:00
2021-11-15 01:08:32 -04:00
# if AP_SCRIPTING_ENABLED
2019-03-01 02:40:18 -04:00
AP_Scripting scripting ;
# endif
2015-06-01 02:04:25 -03:00
// Vehicle state
struct {
bool location_valid ; // true if we have a valid location for the vehicle
Location location ; // lat, long in degrees * 10^7; alt in meters * 100
Location location_estimate ; // lat, long in degrees * 10^7; alt in meters * 100
2016-06-13 05:50:41 -03:00
uint32_t last_update_us ; // last position update in microseconds
2015-06-01 02:04:25 -03:00
uint32_t last_update_ms ; // last position update in milliseconds
2016-06-13 00:52:03 -03:00
Vector3f vel ; // the vehicle's velocity in m/s
2016-07-06 04:49:52 -03:00
int32_t relative_alt ; // the vehicle's relative altitude in meters * 100
2015-06-01 02:04:25 -03:00
} vehicle ;
// Navigation controller state
2019-09-13 12:41:55 -03:00
struct NavStatus {
2015-06-01 02:04:25 -03:00
float bearing ; // bearing to vehicle in centi-degrees
float distance ; // distance to vehicle in meters
float pitch ; // pitch to vehicle in degrees (positive means vehicle is above tracker, negative means below)
2016-07-13 23:40:49 -03:00
float angle_error_pitch ; // angle error between target and current pitch in centi-degrees
float angle_error_yaw ; // angle error between target and current yaw in centi-degrees
2016-05-24 08:53:57 -03:00
float alt_difference_baro ; // altitude difference between tracker and vehicle in meters according to the barometer. positive value means vehicle is above tracker
float alt_difference_gps ; // altitude difference between tracker and vehicle in meters according to the gps. positive value means vehicle is above tracker
2015-06-01 02:04:25 -03:00
float altitude_offset ; // offset in meters which is added to tracker altitude to align altitude measurements with vehicle's barometer
bool manual_control_yaw : 1 ; // true if tracker yaw is under manual control
bool manual_control_pitch : 1 ; // true if tracker pitch is manually controlled
bool need_altitude_calibration : 1 ; // true if tracker altitude has not been determined (true after startup)
bool scan_reverse_pitch : 1 ; // controls direction of pitch movement in SCAN mode
bool scan_reverse_yaw : 1 ; // controls direction of yaw movement in SCAN mode
2019-09-13 12:41:55 -03:00
} nav_status ;
2015-06-01 02:04:25 -03:00
// setup the var_info table
AP_Param param_loader { var_info } ;
bool target_set = false ;
2019-02-28 17:38:28 -04:00
bool stationary = true ; // are we using the start lat and log?
2015-06-01 02:04:25 -03:00
static const AP_Scheduler : : Task scheduler_tasks [ ] ;
static const AP_Param : : Info var_info [ ] ;
2015-12-27 03:05:14 -04:00
static const struct LogStructure log_structure [ ] ;
2015-06-01 02:04:25 -03:00
2020-01-16 06:25:40 -04:00
// Tracker.cpp
void get_scheduler_tasks ( const AP_Scheduler : : Task * & tasks ,
uint8_t & task_count ,
uint32_t & log_bit ) override ;
2015-06-01 02:04:25 -03:00
void one_second_loop ( ) ;
2015-12-27 03:05:14 -04:00
void ten_hz_logging_loop ( ) ;
2019-08-06 04:09:08 -03:00
void stats_update ( ) ;
2018-09-05 08:41:18 -03:00
// GCS_Mavlink.cpp
void send_nav_controller_output ( mavlink_channel_t chan ) ;
// Log.cpp
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 ( ) ;
void log_init ( void ) ;
// Parameters.cpp
2020-01-16 06:40:52 -04:00
void load_parameters ( void ) override ;
2018-09-05 08:41:18 -03:00
// radio.cpp
2015-06-01 02:04:25 -03:00
void read_radio ( ) ;
2018-09-05 08:41:18 -03:00
// sensors.cpp
2015-06-01 02:04:25 -03:00
void update_ahrs ( ) ;
2019-02-08 15:22:08 -04:00
void compass_save ( ) ;
2015-06-01 02:04:25 -03:00
void update_compass ( void ) ;
void update_GPS ( void ) ;
2018-09-05 08:41:18 -03:00
void handle_battery_failsafe ( const char * type_str , const int8_t action ) ;
// servos.cpp
2015-06-01 02:04:25 -03:00
void init_servos ( ) ;
void update_pitch_servo ( float pitch ) ;
2016-07-13 23:40:49 -03:00
void update_pitch_position_servo ( void ) ;
2021-02-01 12:26:21 -04:00
void update_pitch_onoff_servo ( float pitch ) const ;
2018-09-05 08:41:18 -03:00
void update_pitch_cr_servo ( float pitch ) ;
2015-06-01 02:04:25 -03:00
void update_yaw_servo ( float yaw ) ;
2016-07-13 23:40:49 -03:00
void update_yaw_position_servo ( void ) ;
2021-02-01 12:26:21 -04:00
void update_yaw_onoff_servo ( float yaw ) const ;
2018-09-05 08:41:18 -03:00
void update_yaw_cr_servo ( float yaw ) ;
// system.cpp
2020-01-16 06:25:40 -04:00
void init_ardupilot ( ) override ;
2021-02-01 12:26:21 -04:00
bool get_home_eeprom ( struct Location & loc ) const ;
2019-02-20 21:43:55 -04:00
bool set_home_eeprom ( const Location & temp ) WARN_IF_UNUSED ;
bool set_home ( const Location & temp ) WARN_IF_UNUSED ;
2015-06-01 02:04:25 -03:00
void prepare_servos ( ) ;
2019-09-13 12:41:55 -03:00
void set_mode ( Mode & newmode , ModeReason reason ) ;
bool set_mode ( uint8_t new_mode , ModeReason reason ) override ;
2020-01-09 10:47:07 -04:00
uint8_t get_mode ( ) const override { return ( uint8_t ) mode - > number ( ) ; }
2018-09-05 08:41:18 -03:00
bool should_log ( uint32_t mask ) ;
2019-03-10 07:37:25 -03:00
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 ; }
2018-09-05 08:41:18 -03:00
// tracking.cpp
2015-06-01 02:04:25 -03:00
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 ) ;
2021-02-01 12:26:21 -04:00
void update_armed_disarmed ( ) const ;
2021-06-26 11:21:36 -03:00
bool get_pan_tilt_norm ( float & pan_norm , float & tilt_norm ) const override ;
2015-06-01 02:04:25 -03:00
2020-02-18 19:29:10 -04:00
// Arming/Disarming management class
AP_Arming_Tracker arming ;
2019-03-10 07:37:25 -03:00
// Mission library
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 ) } ;
2015-06-01 02:04:25 -03:00
} ;
extern Tracker tracker ;