2015-06-01 02:04:25 -03:00
|
|
|
#include "Tracker.h"
|
|
|
|
|
2014-08-13 01:43:56 -03:00
|
|
|
// mission storage
|
|
|
|
static const StorageAccess wp_storage(StorageManager::StorageMission);
|
|
|
|
|
2015-06-01 02:04:25 -03:00
|
|
|
static void mavlink_delay_cb_static()
|
|
|
|
{
|
|
|
|
tracker.mavlink_delay_cb();
|
|
|
|
}
|
|
|
|
|
|
|
|
void Tracker::init_tracker()
|
2013-10-13 04:14:13 -03:00
|
|
|
{
|
2015-01-28 01:27:03 -04:00
|
|
|
// initialise console serial port
|
|
|
|
serial_manager.init_console();
|
2013-10-13 04:14:13 -03:00
|
|
|
|
2017-09-12 15:28:42 -03:00
|
|
|
hal.console->printf("\n\nInit %s\n\nFree RAM: %u\n",
|
2018-06-13 08:31:50 -03:00
|
|
|
AP::fwversion().fw_string,
|
2018-05-03 22:20:46 -03:00
|
|
|
(unsigned)hal.util->available_memory());
|
2013-10-13 04:14:13 -03:00
|
|
|
|
|
|
|
// Check the EEPROM format version before loading any parameters from EEPROM
|
|
|
|
load_parameters();
|
|
|
|
|
2016-10-16 19:21:08 -03:00
|
|
|
mavlink_system.sysid = g.sysid_this_mav;
|
|
|
|
|
2015-01-28 01:27:03 -04:00
|
|
|
// initialise serial ports
|
|
|
|
serial_manager.init();
|
2013-10-13 04:14:13 -03:00
|
|
|
|
2016-08-03 04:17:24 -03:00
|
|
|
// setup first port early to allow BoardConfig to report errors
|
2019-06-19 01:33:51 -03:00
|
|
|
gcs().chan(0).setup_uart(0);
|
2016-08-03 04:17:24 -03:00
|
|
|
|
|
|
|
// Register mavlink_delay_cb, which will run anytime you have
|
|
|
|
// more than 5ms remaining in your call to hal.scheduler->delay
|
|
|
|
hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);
|
2018-09-05 05:48:10 -03:00
|
|
|
|
2016-08-03 04:17:24 -03:00
|
|
|
BoardConfig.init();
|
2017-05-06 06:11:29 -03:00
|
|
|
#if HAL_WITH_UAVCAN
|
|
|
|
BoardConfig_CAN.init();
|
|
|
|
#endif
|
2016-08-03 04:17:24 -03:00
|
|
|
|
2017-01-21 02:17:26 -04:00
|
|
|
// initialise notify
|
2018-07-25 22:11:00 -03:00
|
|
|
notify.init();
|
2017-01-21 02:17:26 -04:00
|
|
|
AP_Notify::flags.pre_arm_check = true;
|
|
|
|
AP_Notify::flags.pre_arm_gps_check = true;
|
|
|
|
|
2019-04-26 14:56:25 -03:00
|
|
|
// initialise battery
|
|
|
|
battery.init();
|
|
|
|
|
2013-10-13 04:14:13 -03:00
|
|
|
// init baro before we start the GCS, so that the CLI baro test works
|
2018-04-11 09:55:31 -03:00
|
|
|
barometer.set_log_baro_bit(MASK_LOG_IMU);
|
2013-10-13 04:14:13 -03:00
|
|
|
barometer.init();
|
|
|
|
|
2016-05-16 00:33:43 -03:00
|
|
|
// setup telem slots with serial ports
|
2019-06-19 01:24:31 -03:00
|
|
|
gcs().setup_uarts();
|
2015-05-02 09:38:58 -03:00
|
|
|
|
2015-12-27 03:05:14 -04:00
|
|
|
#if LOGGING_ENABLED == ENABLED
|
|
|
|
log_init();
|
|
|
|
#endif
|
|
|
|
|
2019-03-01 02:40:18 -04:00
|
|
|
#ifdef ENABLE_SCRIPTING
|
|
|
|
if (!scripting.init()) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_ERROR, "Scripting failed to start");
|
|
|
|
}
|
|
|
|
#endif // ENABLE_SCRIPTING
|
|
|
|
|
2019-02-08 15:22:08 -04:00
|
|
|
// initialise compass
|
2019-03-25 09:42:51 -03:00
|
|
|
AP::compass().set_log_bit(MASK_LOG_COMPASS);
|
2019-03-24 00:26:06 -03:00
|
|
|
AP::compass().init();
|
2013-10-13 04:14:13 -03:00
|
|
|
|
|
|
|
// GPS Initialization
|
2017-06-28 22:19:50 -03:00
|
|
|
gps.set_log_gps_bit(MASK_LOG_GPS);
|
2017-06-27 05:13:05 -03:00
|
|
|
gps.init(serial_manager);
|
2013-10-13 04:14:13 -03:00
|
|
|
|
|
|
|
ahrs.init();
|
|
|
|
ahrs.set_fly_forward(false);
|
|
|
|
|
2015-12-26 00:08:38 -04:00
|
|
|
ins.init(scheduler.get_loop_rate_hz());
|
2013-10-13 04:14:13 -03:00
|
|
|
ahrs.reset();
|
|
|
|
|
2018-03-18 01:15:13 -03:00
|
|
|
barometer.calibrate();
|
2013-10-13 04:14:13 -03:00
|
|
|
|
2019-01-18 00:23:42 -04:00
|
|
|
// initialise AP_Logger library
|
2019-01-18 00:24:08 -04:00
|
|
|
logger.setVehicle_Startup_Writer(FUNCTOR_BIND(&tracker, &Tracker::Log_Write_Vehicle_Startup_Messages, void));
|
2017-05-01 03:22:35 -03:00
|
|
|
|
2015-01-28 01:27:03 -04:00
|
|
|
// set serial ports non-blocking
|
|
|
|
serial_manager.set_blocking_writes_all(false);
|
2013-10-13 04:14:13 -03:00
|
|
|
|
2014-10-06 02:56:25 -03:00
|
|
|
// initialise servos
|
|
|
|
init_servos();
|
2013-10-13 04:14:13 -03:00
|
|
|
|
2014-03-22 05:09:01 -03:00
|
|
|
// use given start positions - useful for indoor testing, and
|
|
|
|
// while waiting for GPS lock
|
2015-08-27 02:38:00 -03:00
|
|
|
// sanity check location
|
2015-10-27 00:50:29 -03:00
|
|
|
if (fabsf(g.start_latitude) <= 90.0f && fabsf(g.start_longitude) <= 180.0f) {
|
2015-08-27 02:38:00 -03:00
|
|
|
current_loc.lat = g.start_latitude * 1.0e7f;
|
|
|
|
current_loc.lng = g.start_longitude * 1.0e7f;
|
2016-07-05 23:03:33 -03:00
|
|
|
} else {
|
2017-07-08 21:28:33 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_NOTICE, "Ignoring invalid START_LATITUDE or START_LONGITUDE parameter");
|
2015-08-27 02:38:00 -03:00
|
|
|
}
|
2014-03-05 01:47:47 -04:00
|
|
|
|
2014-03-22 05:09:01 -03:00
|
|
|
// see if EEPROM has a default location as well
|
2014-04-09 01:30:27 -03:00
|
|
|
if (current_loc.lat == 0 && current_loc.lng == 0) {
|
|
|
|
get_home_eeprom(current_loc);
|
|
|
|
}
|
2014-03-02 03:00:37 -04:00
|
|
|
|
2017-07-08 21:28:33 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"Ready to track");
|
2014-03-02 03:00:37 -04:00
|
|
|
hal.scheduler->delay(1000); // Why????
|
2014-03-06 18:13:53 -04:00
|
|
|
|
2019-03-10 07:54:17 -03:00
|
|
|
switch (g.initial_mode) {
|
|
|
|
case MANUAL:
|
|
|
|
set_mode(MANUAL, MODE_REASON_STARTUP);
|
|
|
|
break;
|
|
|
|
|
|
|
|
case SCAN:
|
|
|
|
set_mode(SCAN, MODE_REASON_STARTUP);
|
|
|
|
break;
|
|
|
|
|
|
|
|
case STOP:
|
|
|
|
set_mode(STOP, MODE_REASON_STARTUP);
|
|
|
|
break;
|
|
|
|
|
|
|
|
case AUTO:
|
|
|
|
default:
|
|
|
|
set_mode(AUTO, MODE_REASON_STARTUP);
|
|
|
|
break;
|
|
|
|
}
|
2014-03-22 05:09:01 -03:00
|
|
|
|
|
|
|
if (g.startup_delay > 0) {
|
|
|
|
// arm servos with trim value to allow them to start up (required
|
|
|
|
// for some servos)
|
|
|
|
prepare_servos();
|
|
|
|
}
|
2014-08-03 04:38:19 -03:00
|
|
|
|
2017-04-29 21:48:00 -03:00
|
|
|
// disable safety if requested
|
|
|
|
BoardConfig.init_safety();
|
2014-03-02 03:00:37 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
fetch HOME from EEPROM
|
|
|
|
*/
|
2015-06-01 02:04:25 -03:00
|
|
|
bool Tracker::get_home_eeprom(struct Location &loc)
|
2014-03-02 03:00:37 -04:00
|
|
|
{
|
|
|
|
// Find out proper location in memory by using the start_byte position + the index
|
|
|
|
// --------------------------------------------------------------------------------
|
|
|
|
if (g.command_total.get() == 0) {
|
2014-03-22 05:09:01 -03:00
|
|
|
return false;
|
2014-03-02 03:00:37 -04:00
|
|
|
}
|
|
|
|
|
2014-03-22 05:09:01 -03:00
|
|
|
// read WP position
|
2019-01-01 23:24:53 -04:00
|
|
|
loc = {
|
|
|
|
int32_t(wp_storage.read_uint32(5)),
|
|
|
|
int32_t(wp_storage.read_uint32(9)),
|
|
|
|
int32_t(wp_storage.read_uint32(1)),
|
2019-03-14 22:44:11 -03:00
|
|
|
Location::AltFrame::ABSOLUTE
|
2019-01-01 23:24:53 -04:00
|
|
|
};
|
2014-03-22 05:09:01 -03:00
|
|
|
|
|
|
|
return true;
|
2014-03-02 03:00:37 -04:00
|
|
|
}
|
|
|
|
|
2019-02-20 21:43:55 -04:00
|
|
|
bool Tracker::set_home_eeprom(const Location &temp)
|
2014-03-02 03:00:37 -04:00
|
|
|
{
|
2019-01-01 23:24:53 -04:00
|
|
|
wp_storage.write_byte(0, 0);
|
2014-08-13 01:43:56 -03:00
|
|
|
wp_storage.write_uint32(1, temp.alt);
|
|
|
|
wp_storage.write_uint32(5, temp.lat);
|
|
|
|
wp_storage.write_uint32(9, temp.lng);
|
2014-03-02 03:00:37 -04:00
|
|
|
|
|
|
|
// Now have a home location in EEPROM
|
|
|
|
g.command_total.set_and_save(1); // At most 1 entry for HOME
|
2019-02-20 21:43:55 -04:00
|
|
|
return true;
|
2014-03-02 03:00:37 -04:00
|
|
|
}
|
|
|
|
|
2019-02-20 21:43:55 -04:00
|
|
|
bool Tracker::set_home(const Location &temp)
|
2014-03-02 03:00:37 -04:00
|
|
|
{
|
2018-05-16 01:49:01 -03:00
|
|
|
// check EKF origin has been set
|
2017-09-18 02:38:26 -03:00
|
|
|
Location ekf_origin;
|
|
|
|
if (ahrs.get_origin(ekf_origin)) {
|
2018-05-29 21:49:29 -03:00
|
|
|
if (!ahrs.set_home(temp)) {
|
2019-02-20 21:43:55 -04:00
|
|
|
return false;
|
2018-05-29 21:49:29 -03:00
|
|
|
}
|
2017-09-18 02:38:26 -03:00
|
|
|
}
|
2019-02-20 21:43:55 -04:00
|
|
|
|
|
|
|
if (!set_home_eeprom(temp)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
current_loc = temp;
|
|
|
|
|
|
|
|
return true;
|
2017-09-18 02:38:26 -03:00
|
|
|
}
|
|
|
|
|
2015-06-01 02:04:25 -03:00
|
|
|
void Tracker::arm_servos()
|
2017-01-06 22:51:56 -04:00
|
|
|
{
|
|
|
|
hal.util->set_soft_armed(true);
|
2019-01-18 00:23:42 -04:00
|
|
|
logger.set_vehicle_armed(true);
|
2014-03-03 20:37:15 -04:00
|
|
|
}
|
|
|
|
|
2015-06-01 02:04:25 -03:00
|
|
|
void Tracker::disarm_servos()
|
2014-03-03 20:37:15 -04:00
|
|
|
{
|
2017-01-06 22:51:56 -04:00
|
|
|
hal.util->set_soft_armed(false);
|
2019-01-18 00:23:42 -04:00
|
|
|
logger.set_vehicle_armed(false);
|
2014-03-03 20:37:15 -04:00
|
|
|
}
|
2014-03-06 18:13:53 -04:00
|
|
|
|
2014-03-22 05:09:01 -03:00
|
|
|
/*
|
|
|
|
setup servos to trim value after initialising
|
|
|
|
*/
|
2015-06-01 02:04:25 -03:00
|
|
|
void Tracker::prepare_servos()
|
2014-03-22 05:09:01 -03:00
|
|
|
{
|
2015-11-19 23:04:37 -04:00
|
|
|
start_time_ms = AP_HAL::millis();
|
2017-01-08 18:30:37 -04:00
|
|
|
SRV_Channels::set_output_limit(SRV_Channel::k_tracker_yaw, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
|
|
|
SRV_Channels::set_output_limit(SRV_Channel::k_tracker_pitch, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
2017-01-06 22:51:56 -04:00
|
|
|
SRV_Channels::calc_pwm();
|
|
|
|
SRV_Channels::output_ch_all();
|
2014-03-22 05:09:01 -03:00
|
|
|
}
|
|
|
|
|
2018-02-21 19:02:00 -04:00
|
|
|
void Tracker::set_mode(enum ControlMode mode, mode_reason_t reason)
|
2014-03-06 18:13:53 -04:00
|
|
|
{
|
2016-12-13 22:06:30 -04:00
|
|
|
if (control_mode == mode) {
|
2014-03-06 18:13:53 -04:00
|
|
|
// don't switch modes if we are already in the correct mode.
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
control_mode = mode;
|
2014-03-22 05:09:01 -03:00
|
|
|
|
|
|
|
switch (control_mode) {
|
|
|
|
case AUTO:
|
|
|
|
case MANUAL:
|
2014-04-09 02:27:56 -03:00
|
|
|
case SCAN:
|
2014-10-06 08:45:07 -03:00
|
|
|
case SERVO_TEST:
|
2014-03-22 05:09:01 -03:00
|
|
|
arm_servos();
|
|
|
|
break;
|
|
|
|
|
|
|
|
case STOP:
|
|
|
|
case INITIALISING:
|
|
|
|
disarm_servos();
|
|
|
|
break;
|
|
|
|
}
|
2016-02-09 04:00:18 -04:00
|
|
|
|
|
|
|
// log mode change
|
2019-01-18 00:24:08 -04:00
|
|
|
logger.Write_Mode(control_mode, reason);
|
2019-06-26 15:21:20 -03:00
|
|
|
gcs().send_message(MSG_HEARTBEAT);
|
2019-03-10 07:49:28 -03:00
|
|
|
|
|
|
|
nav_status.bearing = ahrs.yaw_sensor * 0.01f;
|
2014-03-06 18:13:53 -04:00
|
|
|
}
|
|
|
|
|
2015-12-27 03:05:14 -04:00
|
|
|
/*
|
|
|
|
should we log a message type now?
|
|
|
|
*/
|
|
|
|
bool Tracker::should_log(uint32_t mask)
|
|
|
|
{
|
2019-01-18 00:23:42 -04:00
|
|
|
if (!logger.should_log(mask)) {
|
2017-06-14 20:27:25 -03:00
|
|
|
return false;
|
|
|
|
}
|
2015-12-27 03:05:14 -04:00
|
|
|
return true;
|
|
|
|
}
|