2013-10-13 04:14:13 -03:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
|
|
|
/*
|
|
|
|
Lead developers: Matthew Ridley and Andrew Tridgell
|
|
|
|
|
|
|
|
Please contribute your ideas! See http://dev.ardupilot.com for details
|
|
|
|
|
|
|
|
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/>.
|
|
|
|
*/
|
|
|
|
|
2015-06-01 02:04:25 -03:00
|
|
|
#include "Tracker.h"
|
2013-10-13 04:14:13 -03:00
|
|
|
|
2015-06-03 03:48:43 -03:00
|
|
|
#define SCHED_TASK(func) FUNCTOR_BIND(&tracker, &Tracker::func, void)
|
2014-10-06 02:55:45 -03:00
|
|
|
|
2013-10-13 04:14:13 -03:00
|
|
|
/*
|
|
|
|
scheduler table - all regular tasks apart from the fast_loop()
|
|
|
|
should be listed here, along with how often they should be called
|
|
|
|
(in 20ms units) and the maximum time they are expected to take (in
|
|
|
|
microseconds)
|
|
|
|
*/
|
2015-06-01 02:04:25 -03:00
|
|
|
const AP_Scheduler::Task Tracker::scheduler_tasks[] PROGMEM = {
|
|
|
|
{ SCHED_TASK(update_ahrs), 1, 1000 },
|
|
|
|
{ SCHED_TASK(read_radio), 1, 200 },
|
|
|
|
{ SCHED_TASK(update_tracking), 1, 1000 },
|
|
|
|
{ SCHED_TASK(update_GPS), 5, 4000 },
|
|
|
|
{ SCHED_TASK(update_compass), 5, 1500 },
|
|
|
|
{ SCHED_TASK(update_barometer), 5, 1500 },
|
|
|
|
{ SCHED_TASK(gcs_update), 1, 1700 },
|
|
|
|
{ SCHED_TASK(gcs_data_stream_send), 1, 3000 },
|
|
|
|
{ SCHED_TASK(compass_accumulate), 1, 1500 },
|
|
|
|
{ SCHED_TASK(barometer_accumulate), 1, 900 },
|
|
|
|
{ SCHED_TASK(update_notify), 1, 100 },
|
|
|
|
{ SCHED_TASK(check_usb_mux), 5, 300 },
|
|
|
|
{ SCHED_TASK(gcs_retry_deferred), 1, 1000 },
|
|
|
|
{ SCHED_TASK(one_second_loop), 50, 3900 }
|
2013-10-13 04:14:13 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
/**
|
|
|
|
setup the sketch - called once on startup
|
|
|
|
*/
|
2015-06-01 02:04:25 -03:00
|
|
|
void Tracker::setup()
|
2013-10-13 04:14:13 -03:00
|
|
|
{
|
|
|
|
// load the default values of variables listed in var_info[]
|
|
|
|
AP_Param::setup_sketch_defaults();
|
|
|
|
|
2015-04-26 06:25:42 -03:00
|
|
|
// initialise notify
|
|
|
|
notify.init(false);
|
|
|
|
|
2014-09-29 08:10:35 -03:00
|
|
|
// antenna tracker does not use pre-arm checks or battery failsafe
|
2013-10-13 04:14:13 -03:00
|
|
|
AP_Notify::flags.pre_arm_check = true;
|
2014-12-24 09:26:32 -04:00
|
|
|
AP_Notify::flags.pre_arm_gps_check = true;
|
2013-10-13 04:14:13 -03:00
|
|
|
AP_Notify::flags.failsafe_battery = false;
|
|
|
|
|
|
|
|
init_tracker();
|
|
|
|
|
|
|
|
// initialise the main loop scheduler
|
2015-05-26 01:36:34 -03:00
|
|
|
scheduler.init(&scheduler_tasks[0], sizeof(scheduler_tasks)/sizeof(scheduler_tasks[0]));
|
2013-10-13 04:14:13 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/**
|
|
|
|
loop() is called continuously
|
|
|
|
*/
|
2015-06-01 02:04:25 -03:00
|
|
|
void Tracker::loop()
|
2013-10-13 04:14:13 -03:00
|
|
|
{
|
|
|
|
// wait for an INS sample
|
2014-10-15 20:33:36 -03:00
|
|
|
ins.wait_for_sample();
|
2013-10-13 04:14:13 -03:00
|
|
|
|
|
|
|
// tell the scheduler one tick has passed
|
|
|
|
scheduler.tick();
|
|
|
|
|
|
|
|
scheduler.run(19900UL);
|
|
|
|
}
|
|
|
|
|
2015-06-01 02:04:25 -03:00
|
|
|
void Tracker::one_second_loop()
|
2013-10-13 04:14:13 -03:00
|
|
|
{
|
|
|
|
// send a heartbeat
|
|
|
|
gcs_send_message(MSG_HEARTBEAT);
|
|
|
|
|
|
|
|
// make it possible to change orientation at runtime
|
|
|
|
ahrs.set_orientation();
|
|
|
|
|
|
|
|
// sync MAVLink system ID
|
|
|
|
mavlink_system.sysid = g.sysid_this_mav;
|
|
|
|
|
2014-09-29 07:40:25 -03:00
|
|
|
// updated armed/disarmed status LEDs
|
|
|
|
update_armed_disarmed();
|
|
|
|
|
2015-06-01 02:04:25 -03:00
|
|
|
one_second_counter++;
|
2013-10-13 04:14:13 -03:00
|
|
|
|
2015-06-01 02:04:25 -03:00
|
|
|
if (one_second_counter >= 60) {
|
2013-10-13 04:14:13 -03:00
|
|
|
if(g.compass_enabled) {
|
|
|
|
compass.save_offsets();
|
|
|
|
}
|
2015-06-01 02:04:25 -03:00
|
|
|
one_second_counter = 0;
|
2013-10-13 04:14:13 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-06-01 02:04:25 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
|
|
|
// needed for APM1 inertialsensor driver
|
|
|
|
AP_ADC_ADS7844 apm1_adc;
|
|
|
|
#endif
|
|
|
|
|
|
|
|
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
|
|
|
|
|
|
|
Tracker::Tracker(void)
|
2015-06-08 01:14:10 -03:00
|
|
|
{
|
|
|
|
memset(¤t_loc, 0, sizeof(current_loc));
|
|
|
|
memset(&vehicle, 0, sizeof(vehicle));
|
|
|
|
}
|
2015-06-01 02:04:25 -03:00
|
|
|
|
|
|
|
Tracker tracker;
|
|
|
|
|
|
|
|
/*
|
|
|
|
compatibility with old pde style build
|
|
|
|
*/
|
|
|
|
void setup(void);
|
|
|
|
void loop(void);
|
|
|
|
|
|
|
|
void setup(void)
|
|
|
|
{
|
|
|
|
tracker.setup();
|
|
|
|
}
|
|
|
|
void loop(void)
|
|
|
|
{
|
|
|
|
tracker.loop();
|
|
|
|
}
|
|
|
|
|
2013-10-13 04:14:13 -03:00
|
|
|
AP_HAL_MAIN();
|