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/system.cpp
Views: 1798
#include "Tracker.h"12// mission storage3static const StorageAccess wp_storage(StorageManager::StorageMission);45void Tracker::init_ardupilot()6{7// initialise notify8notify.init();9AP_Notify::flags.pre_arm_check = true;10AP_Notify::flags.pre_arm_gps_check = true;1112// initialise battery13battery.init();1415// init baro before we start the GCS, so that the CLI baro test works16barometer.set_log_baro_bit(MASK_LOG_IMU);17barometer.init();1819// setup telem slots with serial ports20gcs().setup_uarts();21// update_send so that if the first packet we receive happens to22// be an arm message we don't trigger an internal error when we23// try to initialise stream rates in the main loop.24gcs().update_send();2526// initialise compass27AP::compass().set_log_bit(MASK_LOG_COMPASS);28AP::compass().init();2930// GPS Initialization31gps.set_log_gps_bit(MASK_LOG_GPS);32gps.init();3334ahrs.init();35ahrs.set_fly_forward(false);3637ins.init(scheduler.get_loop_rate_hz());38ahrs.reset();3940barometer.calibrate();4142#if HAL_LOGGING_ENABLED43// initialise AP_Logger library44logger.setVehicle_Startup_Writer(FUNCTOR_BIND(&tracker, &Tracker::Log_Write_Vehicle_Startup_Messages, void));45#endif4647// initialise rc channels including setting mode48rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM);49rc().init();5051// initialise servos52init_servos();5354// use given start positions - useful for indoor testing, and55// while waiting for GPS lock56// sanity check location57if (fabsf(g.start_latitude) <= 90.0f && fabsf(g.start_longitude) <= 180.0f) {58current_loc.lat = g.start_latitude * 1.0e7f;59current_loc.lng = g.start_longitude * 1.0e7f;60} else {61gcs().send_text(MAV_SEVERITY_NOTICE, "Ignoring invalid START_LATITUDE or START_LONGITUDE parameter");62}6364// see if EEPROM has a default location as well65if (current_loc.lat == 0 && current_loc.lng == 0) {66get_home_eeprom(current_loc);67}6869hal.scheduler->delay(1000); // Why????7071Mode *newmode = mode_from_mode_num((Mode::Number)g.initial_mode.get());72if (newmode == nullptr) {73newmode = &mode_manual;74}75set_mode(*newmode, ModeReason::STARTUP);7677if (g.startup_delay > 0) {78// arm servos with trim value to allow them to start up (required79// for some servos)80prepare_servos();81}82}8384/*85fetch HOME from EEPROM86*/87bool Tracker::get_home_eeprom(Location &loc) const88{89// Find out proper location in memory by using the start_byte position + the index90// --------------------------------------------------------------------------------91if (g.command_total.get() == 0) {92return false;93}9495// read WP position96loc = {97int32_t(wp_storage.read_uint32(5)),98int32_t(wp_storage.read_uint32(9)),99int32_t(wp_storage.read_uint32(1)),100Location::AltFrame::ABSOLUTE101};102103return true;104}105106bool Tracker::set_home_eeprom(const Location &temp)107{108wp_storage.write_byte(0, 0);109wp_storage.write_uint32(1, temp.alt);110wp_storage.write_uint32(5, temp.lat);111wp_storage.write_uint32(9, temp.lng);112113// Now have a home location in EEPROM114g.command_total.set_and_save(1); // At most 1 entry for HOME115return true;116}117118bool Tracker::set_home_to_current_location(bool lock)119{120return set_home(AP::gps().location(), lock);121}122123bool Tracker::set_home(const Location &temp, bool lock)124{125// check EKF origin has been set126Location ekf_origin;127if (ahrs.get_origin(ekf_origin)) {128if (!ahrs.set_home(temp)) {129return false;130}131}132133if (!set_home_eeprom(temp)) {134return false;135}136137current_loc = temp;138139return true;140}141142void Tracker::arm_servos()143{144hal.util->set_soft_armed(true);145#if HAL_LOGGING_ENABLED146logger.set_vehicle_armed(true);147#endif148}149150void Tracker::disarm_servos()151{152hal.util->set_soft_armed(false);153#if HAL_LOGGING_ENABLED154logger.set_vehicle_armed(false);155#endif156}157158/*159setup servos to trim value after initialising160*/161void Tracker::prepare_servos()162{163start_time_ms = AP_HAL::millis();164SRV_Channels::set_output_limit(SRV_Channel::k_tracker_yaw, SRV_Channel::Limit::TRIM);165SRV_Channels::set_output_limit(SRV_Channel::k_tracker_pitch, SRV_Channel::Limit::TRIM);166SRV_Channels::calc_pwm();167SRV_Channels::output_ch_all();168}169170void Tracker::set_mode(Mode &newmode, const ModeReason reason)171{172control_mode_reason = reason;173174if (mode == &newmode) {175// don't switch modes if we are already in the correct mode.176return;177}178mode = &newmode;179180if (mode->requires_armed_servos()) {181arm_servos();182} else {183disarm_servos();184}185186#if HAL_LOGGING_ENABLED187// log mode change188logger.Write_Mode((uint8_t)mode->number(), reason);189#endif190gcs().send_message(MSG_HEARTBEAT);191192nav_status.bearing = ahrs.yaw_sensor * 0.01f;193}194195bool Tracker::set_mode(const uint8_t new_mode, const ModeReason reason)196{197Mode *fred = nullptr;198switch ((Mode::Number)new_mode) {199case Mode::Number::INITIALISING:200return false;201case Mode::Number::AUTO:202fred = &mode_auto;203break;204case Mode::Number::MANUAL:205fred = &mode_manual;206break;207case Mode::Number::SCAN:208fred = &mode_scan;209break;210case Mode::Number::SERVOTEST:211fred = &mode_servotest;212break;213case Mode::Number::STOP:214fred = &mode_stop;215break;216case Mode::Number::GUIDED:217fred = &mode_guided;218break;219}220if (fred == nullptr) {221return false;222}223set_mode(*fred, reason);224return true;225}226227#if HAL_LOGGING_ENABLED228/*229should we log a message type now?230*/231bool Tracker::should_log(uint32_t mask)232{233if (!logger.should_log(mask)) {234return false;235}236return true;237}238#endif239240#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>241#include <AP_Avoidance/AP_Avoidance.h>242#include <AP_ADSB/AP_ADSB.h>243244#if AP_ADVANCEDFAILSAFE_ENABLED245// dummy method to avoid linking AFS246bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) {return false;}247AP_AdvancedFailsafe *AP::advancedfailsafe() { return nullptr; }248#endif // AP_ADVANCEDFAILSAFE_ENABLED249#if HAL_ADSB_ENABLED250// dummy method to avoid linking AP_Avoidance251AP_Avoidance *AP::ap_avoidance() { return nullptr; }252#endif253254255