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.cpp
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*/1819#include "Tracker.h"2021#define FORCE_VERSION_H_INCLUDE22#include "version.h"23#undef FORCE_VERSION_H_INCLUDE2425#define SCHED_TASK(func, _interval_ticks, _max_time_micros, _prio) SCHED_TASK_CLASS(Tracker, &tracker, func, _interval_ticks, _max_time_micros, _prio)2627/*28All entries in this table must be ordered by priority.2930This table is interleaved with the table in AP_Vehicle to determine31the order in which tasks are run. Convenience methods SCHED_TASK32and SCHED_TASK_CLASS are provided to build entries in this structure:3334SCHED_TASK arguments:35- name of static function to call36- rate (in Hertz) at which the function should be called37- expected time (in MicroSeconds) that the function should take to run38- priority (0 through 255, lower number meaning higher priority)3940SCHED_TASK_CLASS arguments:41- class name of method to be called42- instance on which to call the method43- method to call on that instance44- rate (in Hertz) at which the method should be called45- expected time (in MicroSeconds) that the method should take to run46- priority (0 through 255, lower number meaning higher priority)4748*/49const AP_Scheduler::Task Tracker::scheduler_tasks[] = {50SCHED_TASK(update_ahrs, 50, 1000, 5),51SCHED_TASK(read_radio, 50, 200, 10),52SCHED_TASK(update_tracking, 50, 1000, 15),53SCHED_TASK(update_GPS, 10, 4000, 20),54SCHED_TASK(update_compass, 10, 1500, 25),55SCHED_TASK(compass_save, 0.02, 200, 30),56SCHED_TASK_CLASS(AP_BattMonitor, &tracker.battery, read, 10, 1500, 35),57SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, update, 10, 1500, 40),58SCHED_TASK_CLASS(GCS, (GCS*)&tracker._gcs, update_receive, 50, 1700, 45),59SCHED_TASK_CLASS(GCS, (GCS*)&tracker._gcs, update_send, 50, 3000, 50),60#if HAL_LOGGING_ENABLED61SCHED_TASK(ten_hz_logging_loop, 10, 300, 60),62SCHED_TASK_CLASS(AP_Logger, &tracker.logger, periodic_tasks, 50, 300, 65),63#endif64SCHED_TASK_CLASS(AP_InertialSensor, &tracker.ins, periodic, 50, 50, 70),65SCHED_TASK(one_second_loop, 1, 3900, 80),66SCHED_TASK(stats_update, 1, 200, 90),67};6869void Tracker::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,70uint8_t &task_count,71uint32_t &log_bit)72{73tasks = &scheduler_tasks[0];74task_count = ARRAY_SIZE(scheduler_tasks);75log_bit = (uint32_t)-1;76}7778void Tracker::one_second_loop()79{80// sync MAVLink system ID81mavlink_system.sysid = g.sysid_this_mav;8283// update assigned functions and enable auxiliary servos84AP::srv().enable_aux_servos();8586// updated armed/disarmed status LEDs87update_armed_disarmed();8889if (!ahrs.home_is_set()) {90// set home to current location91Location temp_loc;92if (ahrs.get_location(temp_loc)) {93if (!set_home(temp_loc, false)) {94// fail silently95}96}97}9899// need to set "likely flying" when armed to allow for compass100// learning to run101set_likely_flying(hal.util->get_soft_armed());102103AP_Notify::flags.flying = hal.util->get_soft_armed();104105g.pidYaw2Srv.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());106}107108#if HAL_LOGGING_ENABLED109void Tracker::ten_hz_logging_loop()110{111if (should_log(MASK_LOG_IMU)) {112AP::ins().Write_IMU();113}114if (should_log(MASK_LOG_ATTITUDE)) {115Log_Write_Attitude();116}117if (should_log(MASK_LOG_RCIN)) {118logger.Write_RCIN();119}120if (should_log(MASK_LOG_RCOUT)) {121logger.Write_RCOUT();122}123}124#endif125126Mode *Tracker::mode_from_mode_num(const Mode::Number num)127{128Mode *ret = nullptr;129switch (num) {130case Mode::Number::MANUAL:131ret = &mode_manual;132break;133case Mode::Number::STOP:134ret = &mode_stop;135break;136case Mode::Number::SCAN:137ret = &mode_scan;138break;139case Mode::Number::GUIDED:140ret = &mode_guided;141break;142case Mode::Number::SERVOTEST:143ret = &mode_servotest;144break;145case Mode::Number::AUTO:146ret = &mode_auto;147break;148case Mode::Number::INITIALISING:149ret = &mode_initialising;150break;151}152return ret;153}154155/*156update AP_Stats157*/158void Tracker::stats_update(void)159{160AP::stats()->set_flying(hal.util->get_soft_armed());161}162163const AP_HAL::HAL& hal = AP_HAL::get_HAL();164165Tracker tracker;166AP_Vehicle& vehicle = tracker;167168AP_HAL_MAIN_CALLBACKS(&tracker);169170171