2015-06-01 02:04:25 -03:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
Lead developers : Matthew Ridley and Andrew Tridgell
2016-05-05 19:10:08 -03:00
2016-04-23 17:52:26 -03:00
Please contribute your ideas ! See http : //dev.ardupilot.org 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_HAL/AP_HAL.h>
# include <AP_Param/AP_Param.h>
# include <StorageManager/StorageManager.h>
# include <AP_GPS/AP_GPS.h> // ArduPilot GPS library
# include <AP_Baro/AP_Baro.h> // ArduPilot barometer library
# include <AP_Compass/AP_Compass.h> // ArduPilot Mega Magnetometer Library
# include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
# include <AP_ADC/AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
# include <AP_InertialSensor/AP_InertialSensor.h> // Inertial Sensor Library
2015-10-21 18:27:35 -03:00
# include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
2015-08-11 03:28:40 -03:00
# include <AP_AHRS/AP_AHRS.h> // ArduPilot Mega DCM Library
# include <Filter/Filter.h> // Filter library
# include <AP_Buffer/AP_Buffer.h> // APM FIFO Buffer
# include <AP_SerialManager/AP_SerialManager.h> // Serial manager library
# include <AP_Declination/AP_Declination.h> // ArduPilot Mega Declination Helper Library
# include <DataFlash/DataFlash.h>
2016-06-16 00:07:07 -03:00
# include <AC_PID/AC_PID.h>
2015-08-11 03:28:40 -03:00
# include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler
# include <AP_NavEKF/AP_NavEKF.h>
2015-09-22 22:51:47 -03:00
# include <AP_NavEKF2/AP_NavEKF2.h>
2015-08-11 03:28:40 -03:00
# include <AP_Vehicle/AP_Vehicle.h>
# include <AP_Mission/AP_Mission.h>
# include <AP_Terrain/AP_Terrain.h>
# include <AP_Rally/AP_Rally.h>
# include <AP_Notify/AP_Notify.h> // Notify library
# include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
# include <AP_Airspeed/AP_Airspeed.h>
# include <RC_Channel/RC_Channel.h>
# include <AP_BoardConfig/AP_BoardConfig.h>
# include <AP_OpticalFlow/AP_OpticalFlow.h>
# include <AP_RangeFinder/AP_RangeFinder.h>
2015-06-01 02:04:25 -03:00
// Configuration
# include "config.h"
# include "defines.h"
# include "Parameters.h"
2016-05-27 10:14:08 -03:00
# include "GCS_Mavlink.h"
2015-08-11 03:28:40 -03:00
2015-10-22 12:36:14 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
# include <SITL/SITL.h>
# endif
2015-10-19 15:32:37 -03:00
class Tracker : public AP_HAL : : HAL : : Callbacks {
2015-06-01 02:04:25 -03:00
public :
2016-05-27 10:14:08 -03:00
friend class GCS_MAVLINK_Tracker ;
2015-06-01 02:04:25 -03:00
friend class Parameters ;
Tracker ( void ) ;
2015-10-19 15:32:37 -03:00
// HAL::Callbacks implementation.
void setup ( ) override ;
void loop ( ) override ;
2015-06-01 02:04:25 -03:00
private :
Parameters g ;
// main loop scheduler
AP_Scheduler scheduler ;
// notification object for LEDs, buzzers etc
AP_Notify notify ;
2015-06-08 01:14:10 -03:00
uint32_t start_time_ms = 0 ;
2015-06-01 02:04:25 -03:00
2015-06-08 01:14:10 -03:00
bool usb_connected = false ;
2015-06-01 02:04:25 -03:00
2015-12-27 03:05:14 -04:00
// has a log download started?
bool in_log_download = false ;
bool logging_started = false ;
2016-05-05 19:10:08 -03:00
DataFlash_Class DataFlash ;
2015-12-27 03:05:14 -04:00
2015-06-01 02:04:25 -03:00
AP_GPS gps ;
AP_Baro barometer ;
Compass compass ;
AP_InertialSensor ins ;
2015-09-07 03:12:31 -03:00
RangeFinder rng { serial_manager } ;
2015-06-01 02:04:25 -03:00
// Inertial Navigation EKF
# if AP_AHRS_NAVEKF_AVAILABLE
2015-06-01 03:17:07 -03:00
NavEKF EKF { & ahrs , barometer , rng } ;
2015-09-22 22:51:47 -03:00
NavEKF2 EKF2 { & ahrs , barometer , rng } ;
AP_AHRS_NavEKF ahrs { ins , barometer , gps , rng , EKF , EKF2 } ;
2015-06-01 02:04:25 -03:00
# else
AP_AHRS_DCM ahrs { ins , barometer , gps } ;
# endif
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
2015-10-22 10:04:42 -03:00
SITL : : SITL sitl ;
2015-06-01 02:04:25 -03:00
# endif
/**
antenna control channels
*/
RC_Channel channel_yaw { CH_YAW } ;
RC_Channel channel_pitch { CH_PITCH } ;
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 ;
2015-06-01 02:04:25 -03:00
AP_SerialManager serial_manager ;
const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS ;
2016-05-27 10:14:08 -03:00
GCS_MAVLINK_Tracker gcs [ MAVLINK_COMM_NUM_BUFFERS ] ;
2015-06-01 02:04:25 -03:00
AP_BoardConfig BoardConfig ;
struct Location current_loc ;
enum ControlMode control_mode = INITIALISING ;
// 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
struct {
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
2016-07-13 23:40:49 -03:00
} nav_status = { 0.0f , 0.0f , 0.0f , 0.0f , 0.0f , 0.0f , 0.0f , 0.0f , false , false , true , false , false } ;
2015-06-01 02:04:25 -03:00
// setup the var_info table
AP_Param param_loader { var_info } ;
uint8_t one_second_counter = 0 ;
bool target_set = false ;
2015-12-27 03:05:14 -04:00
// use this to prevent recursion during sensor init
bool in_mavlink_delay = false ;
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
2015-12-27 03:05:14 -04:00
void dataflash_periodic ( void ) ;
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 ( ) ;
2015-06-01 02:04:25 -03:00
void send_heartbeat ( mavlink_channel_t chan ) ;
void send_attitude ( mavlink_channel_t chan ) ;
void send_location ( mavlink_channel_t chan ) ;
void send_hwstatus ( mavlink_channel_t chan ) ;
void send_waypoint_request ( mavlink_channel_t chan ) ;
void send_nav_controller_output ( mavlink_channel_t chan ) ;
void send_simstate ( mavlink_channel_t chan ) ;
void mavlink_check_target ( const mavlink_message_t * msg ) ;
void gcs_send_message ( enum ap_message id ) ;
void gcs_data_stream_send ( void ) ;
void gcs_update ( void ) ;
2015-10-26 08:25:44 -03:00
void gcs_send_text ( MAV_SEVERITY severity , const char * str ) ;
2015-06-01 02:04:25 -03:00
void gcs_retry_deferred ( void ) ;
void load_parameters ( void ) ;
void update_auto ( void ) ;
2016-07-27 23:31:48 -03:00
void calc_angle_error ( float pitch , float yaw , bool direction_reversed ) ;
void convert_ef_to_bf ( float pitch , float yaw , float & bf_pitch , float & bf_yaw ) ;
bool convert_bf_to_ef ( float pitch , float yaw , float & ef_pitch , float & ef_yaw ) ;
bool get_ef_yaw_direction ( ) ;
2015-06-01 02:04:25 -03:00
void update_manual ( void ) ;
void update_scan ( void ) ;
bool servo_test_set_servo ( uint8_t servo_num , uint16_t pwm ) ;
void read_radio ( ) ;
2016-05-23 22:31:41 -03:00
void init_barometer ( bool full_calibration ) ;
2015-06-01 02:04:25 -03:00
void update_barometer ( void ) ;
void update_ahrs ( ) ;
void update_compass ( void ) ;
void compass_accumulate ( void ) ;
2015-10-21 18:27:35 -03:00
void accel_cal_update ( void ) ;
2015-06-01 02:04:25 -03:00
void barometer_accumulate ( void ) ;
void update_GPS ( void ) ;
void init_servos ( ) ;
void update_pitch_servo ( float pitch ) ;
2016-07-13 23:40:49 -03:00
void update_pitch_position_servo ( void ) ;
2015-06-03 11:05:58 -03:00
void update_pitch_cr_servo ( float pitch ) ;
2015-06-01 02:04:25 -03:00
void update_pitch_onoff_servo ( float pitch ) ;
void update_yaw_servo ( float yaw ) ;
2016-07-13 23:40:49 -03:00
void update_yaw_position_servo ( void ) ;
2015-06-03 11:05:58 -03:00
void update_yaw_cr_servo ( float yaw ) ;
2015-06-01 02:04:25 -03:00
void update_yaw_onoff_servo ( float yaw ) ;
void init_tracker ( ) ;
void update_notify ( ) ;
bool get_home_eeprom ( struct Location & loc ) ;
void set_home_eeprom ( struct Location temp ) ;
void set_home ( struct Location temp ) ;
void arm_servos ( ) ;
void disarm_servos ( ) ;
void prepare_servos ( ) ;
void set_mode ( enum ControlMode mode ) ;
bool mavlink_set_mode ( uint8_t mode ) ;
void check_usb_mux ( void ) ;
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 ( ) ;
2015-11-03 20:57:18 -04:00
void gcs_send_text_fmt ( MAV_SEVERITY severity , const char * fmt , . . . ) ;
2015-07-31 19:30:03 -03:00
void init_capabilities ( void ) ;
2015-07-31 02:52:02 -03:00
void compass_cal_update ( ) ;
2015-12-27 03:05:14 -04:00
void Log_Write_Attitude ( ) ;
void Log_Write_Baro ( void ) ;
2016-06-13 00:52:03 -03:00
void Log_Write_Vehicle_Pos ( int32_t lat , int32_t lng , int32_t alt , const Vector3f & vel ) ;
2016-05-12 02:17:31 -03:00
void Log_Write_Vehicle_Baro ( float pressure , float altitude ) ;
2015-12-27 03:05:14 -04:00
void Log_Write_Vehicle_Startup_Messages ( ) ;
void start_logging ( ) ;
void log_init ( void ) ;
bool should_log ( uint32_t mask ) ;
2015-06-01 02:04:25 -03:00
public :
void mavlink_snoop ( const mavlink_message_t * msg ) ;
void mavlink_delay_cb ( ) ;
} ;
# define MENU_FUNC(func) FUNCTOR_BIND(&tracker, &Tracker::func, int8_t, uint8_t, const Menu::arg *)
extern const AP_HAL : : HAL & hal ;
extern Tracker tracker ;