2013-08-26 03:52:24 -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/>.
|
|
|
|
*/
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2015-05-24 19:59:16 -03:00
|
|
|
/*
|
2013-08-26 03:52:24 -03:00
|
|
|
This is the APMrover2 firmware. It was originally derived from
|
|
|
|
ArduPlane by Jean-Louis Naudin (JLN), and then rewritten after the
|
|
|
|
AP_HAL merge by Andrew Tridgell
|
|
|
|
|
2015-08-05 23:32:42 -03:00
|
|
|
Maintainer: Grant Morphett
|
2013-02-28 21:32:48 -04:00
|
|
|
|
2015-08-05 23:32:42 -03:00
|
|
|
Authors: Doug Weibel, Jose Julio, Jordi Munoz, Jason Short, Andrew Tridgell, Randy Mackay, Pat Hickey, John Arne Birkeland, Olivier Adler, Jean-Louis Naudin, Grant Morphett
|
2013-02-28 21:32:48 -04:00
|
|
|
|
2013-08-26 03:52:24 -03:00
|
|
|
Thanks to: Chris Anderson, Michael Oborne, Paul Mather, Bill Premerlani, James Cohen, JB from rotorFX, Automatik, Fefenin, Peter Meister, Remzibi, Yury Smirnov, Sandro Benigno, Max Levine, Roberto Navoni, Lorenz Meier
|
2012-05-14 12:47:08 -03:00
|
|
|
|
2015-05-24 19:59:16 -03:00
|
|
|
APMrover alpha version tester: Franco Borasio, Daniel Chapelat...
|
2013-08-26 03:52:24 -03:00
|
|
|
|
2016-04-23 18:01:24 -03:00
|
|
|
Please contribute your ideas! See http://dev.ardupilot.org for details
|
2013-08-26 03:52:24 -03:00
|
|
|
*/
|
2013-02-28 21:32:48 -04:00
|
|
|
|
2015-05-12 02:03:23 -03:00
|
|
|
#include "Rover.h"
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2015-10-16 17:22:11 -03:00
|
|
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
2012-11-21 02:25:11 -04:00
|
|
|
|
2015-05-13 00:16:45 -03:00
|
|
|
Rover rover;
|
2013-06-03 21:37:05 -03:00
|
|
|
|
2015-12-26 00:05:34 -04:00
|
|
|
#define SCHED_TASK(func, _interval_ticks, _max_time_micros) SCHED_TASK_CLASS(Rover, &rover, func, _interval_ticks, _max_time_micros)
|
2015-05-12 04:00:25 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
scheduler table - all regular tasks 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-10-25 14:03:46 -03:00
|
|
|
const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
2015-12-26 00:05:34 -04:00
|
|
|
SCHED_TASK(read_radio, 50, 1000),
|
|
|
|
SCHED_TASK(ahrs_update, 50, 6400),
|
|
|
|
SCHED_TASK(read_sonars, 50, 2000),
|
|
|
|
SCHED_TASK(update_current_mode, 50, 1500),
|
|
|
|
SCHED_TASK(set_servos, 50, 1500),
|
|
|
|
SCHED_TASK(update_GPS_50Hz, 50, 2500),
|
|
|
|
SCHED_TASK(update_GPS_10Hz, 10, 2500),
|
|
|
|
SCHED_TASK(update_alt, 10, 3400),
|
2017-04-03 17:46:12 -03:00
|
|
|
SCHED_TASK(update_beacon, 50, 50),
|
2015-12-26 00:05:34 -04:00
|
|
|
SCHED_TASK(navigate, 10, 1600),
|
|
|
|
SCHED_TASK(update_compass, 10, 2000),
|
|
|
|
SCHED_TASK(update_commands, 10, 1000),
|
|
|
|
SCHED_TASK(update_logging1, 10, 1000),
|
|
|
|
SCHED_TASK(update_logging2, 10, 1000),
|
|
|
|
SCHED_TASK(gcs_retry_deferred, 50, 1000),
|
|
|
|
SCHED_TASK(gcs_update, 50, 1700),
|
|
|
|
SCHED_TASK(gcs_data_stream_send, 50, 3000),
|
2015-07-28 11:02:31 -03:00
|
|
|
SCHED_TASK(read_control_switch, 7, 1000),
|
2015-12-26 00:05:34 -04:00
|
|
|
SCHED_TASK(read_trim_switch, 10, 1000),
|
|
|
|
SCHED_TASK(read_battery, 10, 1000),
|
|
|
|
SCHED_TASK(read_receiver_rssi, 10, 1000),
|
|
|
|
SCHED_TASK(update_events, 50, 1000),
|
|
|
|
SCHED_TASK(check_usb_mux, 3, 1000),
|
|
|
|
SCHED_TASK(mount_update, 50, 600),
|
2016-01-19 01:26:14 -04:00
|
|
|
SCHED_TASK(update_trigger, 50, 600),
|
2015-12-26 00:05:34 -04:00
|
|
|
SCHED_TASK(gcs_failsafe_check, 10, 600),
|
|
|
|
SCHED_TASK(compass_accumulate, 50, 900),
|
|
|
|
SCHED_TASK(update_notify, 50, 300),
|
|
|
|
SCHED_TASK(one_second_loop, 1, 3000),
|
2016-12-20 09:26:57 -04:00
|
|
|
SCHED_TASK(compass_cal_update, 50, 100),
|
2015-10-21 18:22:45 -03:00
|
|
|
SCHED_TASK(accel_cal_update, 10, 100),
|
2015-12-26 00:05:34 -04:00
|
|
|
SCHED_TASK(dataflash_periodic, 50, 300),
|
2016-12-20 09:26:57 -04:00
|
|
|
SCHED_TASK(button_update, 5, 100),
|
|
|
|
SCHED_TASK(stats_update, 1, 100),
|
|
|
|
SCHED_TASK(crash_check, 10, 1000),
|
2017-01-30 10:21:55 -04:00
|
|
|
#if ADVANCED_FAILSAFE == ENABLED
|
|
|
|
SCHED_TASK(afs_fs_check, 10, 100),
|
|
|
|
#endif
|
2015-05-12 04:00:25 -03:00
|
|
|
};
|
|
|
|
|
2016-10-25 23:19:28 -03:00
|
|
|
/*
|
|
|
|
update AP_Stats
|
|
|
|
*/
|
|
|
|
void Rover::stats_update(void)
|
|
|
|
{
|
|
|
|
g2.stats.set_flying(motor_active());
|
|
|
|
g2.stats.update();
|
|
|
|
}
|
|
|
|
|
2013-06-03 21:37:05 -03:00
|
|
|
/*
|
|
|
|
setup is called when the sketch starts
|
|
|
|
*/
|
2016-12-20 09:26:57 -04:00
|
|
|
void Rover::setup()
|
2015-05-12 02:03:23 -03:00
|
|
|
{
|
2012-12-18 07:44:12 -04:00
|
|
|
cliSerial = hal.console;
|
|
|
|
|
2012-12-18 16:17:17 -04:00
|
|
|
// load the default values of variables listed in var_info[]
|
|
|
|
AP_Param::setup_sketch_defaults();
|
|
|
|
|
2017-03-15 00:00:14 -03:00
|
|
|
in_auto_reverse = false;
|
2017-01-31 05:46:32 -04:00
|
|
|
|
2015-08-28 03:00:12 -03:00
|
|
|
rssi.init();
|
2012-12-18 07:44:12 -04:00
|
|
|
|
2015-03-02 01:57:36 -04:00
|
|
|
init_ardupilot();
|
2013-06-03 21:37:05 -03:00
|
|
|
|
|
|
|
// initialise the main loop scheduler
|
2015-07-06 12:30:40 -03:00
|
|
|
scheduler.init(&scheduler_tasks[0], ARRAY_SIZE(scheduler_tasks));
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2013-06-03 21:37:05 -03:00
|
|
|
/*
|
|
|
|
loop() is called rapidly while the sketch is running
|
|
|
|
*/
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::loop()
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2013-10-08 03:30:55 -03:00
|
|
|
// wait for an INS sample
|
2014-10-15 20:33:46 -03:00
|
|
|
ins.wait_for_sample();
|
|
|
|
|
2017-01-31 06:12:26 -04:00
|
|
|
const uint32_t timer = AP_HAL::micros();
|
2013-06-03 21:37:05 -03:00
|
|
|
|
2015-05-24 19:59:16 -03:00
|
|
|
delta_us_fast_loop = timer - fast_loopTimer_us;
|
2013-10-28 03:21:35 -03:00
|
|
|
G_Dt = delta_us_fast_loop * 1.0e-6f;
|
|
|
|
fast_loopTimer_us = timer;
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2016-12-20 09:26:57 -04:00
|
|
|
if (delta_us_fast_loop > G_Dt_max) {
|
2015-05-24 19:59:16 -03:00
|
|
|
G_Dt_max = delta_us_fast_loop;
|
2016-12-20 09:26:57 -04:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2013-10-27 20:33:52 -03:00
|
|
|
mainLoop_count++;
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2013-10-08 03:30:55 -03:00
|
|
|
// tell the scheduler one tick has passed
|
|
|
|
scheduler.tick();
|
2015-08-05 00:12:42 -03:00
|
|
|
|
|
|
|
// run all the tasks that are due to run. Note that we only
|
|
|
|
// have to call this once per loop, as the tasks are scheduled
|
|
|
|
// in multiples of the main loop tick. So if they don't run on
|
|
|
|
// the first call to the scheduler they won't run on a later
|
|
|
|
// call until scheduler.tick() is called again
|
|
|
|
uint32_t remaining = (timer + 20000) - micros();
|
|
|
|
if (remaining > 19500) {
|
|
|
|
remaining = 19500;
|
|
|
|
}
|
|
|
|
scheduler.run(remaining);
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2016-07-28 04:31:58 -03:00
|
|
|
void Rover::update_soft_armed()
|
|
|
|
{
|
|
|
|
hal.util->set_soft_armed(arming.is_armed() &&
|
|
|
|
hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED);
|
|
|
|
DataFlash.set_vehicle_armed(hal.util->get_soft_armed());
|
|
|
|
}
|
|
|
|
|
2013-10-27 20:33:52 -03:00
|
|
|
// update AHRS system
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::ahrs_update()
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2016-07-28 04:31:58 -03:00
|
|
|
update_soft_armed();
|
2014-02-18 19:54:04 -04:00
|
|
|
|
2013-10-27 20:33:52 -03:00
|
|
|
#if HIL_MODE != HIL_MODE_DISABLED
|
|
|
|
// update hil before AHRS update
|
|
|
|
gcs_update();
|
|
|
|
#endif
|
2013-02-28 16:40:47 -04:00
|
|
|
|
2013-11-17 19:58:22 -04:00
|
|
|
// when in reverse we need to tell AHRS not to assume we are a
|
|
|
|
// 'fly forward' vehicle, otherwise it will see a large
|
|
|
|
// discrepancy between the mag and the GPS heading and will try to
|
|
|
|
// correct for it, leading to a large yaw error
|
|
|
|
ahrs.set_fly_forward(!in_reverse);
|
|
|
|
|
2013-10-27 20:33:52 -03:00
|
|
|
ahrs.update();
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2014-05-11 08:39:06 -03:00
|
|
|
// if using the EKF get a speed update now (from accelerometers)
|
|
|
|
Vector3f velocity;
|
|
|
|
if (ahrs.get_velocity_NED(velocity)) {
|
2016-04-16 06:58:46 -03:00
|
|
|
ground_speed = norm(velocity.x, velocity.y);
|
2014-05-11 08:39:06 -03:00
|
|
|
}
|
|
|
|
|
2016-12-20 09:26:57 -04:00
|
|
|
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
|
2013-06-03 22:57:59 -03:00
|
|
|
Log_Write_Attitude();
|
2016-12-20 09:26:57 -04:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2015-07-13 08:34:58 -03:00
|
|
|
if (should_log(MASK_LOG_IMU)) {
|
2013-11-03 23:37:54 -04:00
|
|
|
DataFlash.Log_Write_IMU(ins);
|
2015-07-13 08:34:58 -03:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2013-06-03 21:37:05 -03:00
|
|
|
/*
|
|
|
|
update camera mount - 50Hz
|
|
|
|
*/
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::mount_update(void)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
|
|
|
#if MOUNT == ENABLED
|
2015-05-24 19:59:16 -03:00
|
|
|
camera_mount.update();
|
2012-04-30 04:17:14 -03:00
|
|
|
#endif
|
2015-06-07 14:22:06 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
update camera trigger - 50Hz
|
|
|
|
*/
|
|
|
|
void Rover::update_trigger(void)
|
|
|
|
{
|
2013-07-14 20:57:00 -03:00
|
|
|
#if CAMERA == ENABLED
|
|
|
|
camera.trigger_pic_cleanup();
|
2016-01-19 01:26:14 -04:00
|
|
|
if (camera.check_trigger_pin()) {
|
|
|
|
gcs_send_message(MSG_CAMERA_FEEDBACK);
|
|
|
|
if (should_log(MASK_LOG_CAMERA)) {
|
|
|
|
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
|
|
|
|
}
|
2016-12-20 09:26:57 -04:00
|
|
|
}
|
2013-07-14 20:57:00 -03:00
|
|
|
#endif
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::update_alt()
|
2014-02-23 18:25:50 -04:00
|
|
|
{
|
2015-01-05 07:27:45 -04:00
|
|
|
barometer.update();
|
2014-02-23 18:25:50 -04:00
|
|
|
if (should_log(MASK_LOG_IMU)) {
|
|
|
|
Log_Write_Baro();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2013-06-03 21:37:05 -03:00
|
|
|
/*
|
|
|
|
check for GCS failsafe - 10Hz
|
|
|
|
*/
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::gcs_failsafe_check(void)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2015-05-24 19:59:16 -03:00
|
|
|
if (g.fs_gcs_enabled) {
|
2013-09-15 19:23:21 -03:00
|
|
|
failsafe_trigger(FAILSAFE_EVENT_GCS, last_heartbeat_ms != 0 && (millis() - last_heartbeat_ms) > 2000);
|
|
|
|
}
|
2013-06-03 21:37:05 -03:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2013-06-03 21:54:42 -03:00
|
|
|
/*
|
|
|
|
if the compass is enabled then try to accumulate a reading
|
|
|
|
*/
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::compass_accumulate(void)
|
2013-06-03 21:54:42 -03:00
|
|
|
{
|
|
|
|
if (g.compass_enabled) {
|
|
|
|
compass.accumulate();
|
2015-05-24 19:59:16 -03:00
|
|
|
}
|
2013-06-03 21:54:42 -03:00
|
|
|
}
|
|
|
|
|
2013-06-03 21:37:05 -03:00
|
|
|
/*
|
|
|
|
check for new compass data - 10Hz
|
|
|
|
*/
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::update_compass(void)
|
2013-06-03 21:37:05 -03:00
|
|
|
{
|
|
|
|
if (g.compass_enabled && compass.read()) {
|
|
|
|
ahrs.set_compass(&compass);
|
|
|
|
// update offsets
|
2014-02-15 22:22:20 -04:00
|
|
|
compass.learn_offsets();
|
2014-01-14 00:10:13 -04:00
|
|
|
if (should_log(MASK_LOG_COMPASS)) {
|
2015-01-16 18:42:14 -04:00
|
|
|
DataFlash.Log_Write_Compass(compass);
|
2013-06-03 21:37:05 -03:00
|
|
|
}
|
|
|
|
} else {
|
2016-10-28 13:57:14 -03:00
|
|
|
ahrs.set_compass(nullptr);
|
2013-06-03 21:37:05 -03:00
|
|
|
}
|
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2013-06-03 21:37:05 -03:00
|
|
|
/*
|
|
|
|
log some key data - 10Hz
|
|
|
|
*/
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::update_logging1(void)
|
2013-06-03 21:37:05 -03:00
|
|
|
{
|
2016-12-20 09:26:57 -04:00
|
|
|
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) {
|
2013-06-03 21:37:05 -03:00
|
|
|
Log_Write_Attitude();
|
2016-12-20 09:26:57 -04:00
|
|
|
}
|
2015-05-24 19:59:16 -03:00
|
|
|
|
2016-12-20 09:26:57 -04:00
|
|
|
if (should_log(MASK_LOG_CTUN)) {
|
2013-06-03 21:37:05 -03:00
|
|
|
Log_Write_Control_Tuning();
|
2017-04-03 17:46:12 -03:00
|
|
|
Log_Write_Beacon();
|
2016-12-20 09:26:57 -04:00
|
|
|
}
|
2013-06-03 21:37:05 -03:00
|
|
|
|
2016-12-20 09:26:57 -04:00
|
|
|
if (should_log(MASK_LOG_NTUN)) {
|
2013-06-03 21:37:05 -03:00
|
|
|
Log_Write_Nav_Tuning();
|
2016-12-20 09:26:57 -04:00
|
|
|
}
|
2013-12-29 19:24:01 -04:00
|
|
|
}
|
2013-12-15 20:14:58 -04:00
|
|
|
|
2013-12-29 19:24:01 -04:00
|
|
|
/*
|
|
|
|
log some key data - 10Hz
|
|
|
|
*/
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::update_logging2(void)
|
2013-12-29 19:24:01 -04:00
|
|
|
{
|
2014-01-14 00:10:13 -04:00
|
|
|
if (should_log(MASK_LOG_STEERING)) {
|
2013-12-15 20:14:58 -04:00
|
|
|
if (control_mode == STEERING || control_mode == AUTO || control_mode == RTL || control_mode == GUIDED) {
|
|
|
|
Log_Write_Steering();
|
|
|
|
}
|
|
|
|
}
|
2013-12-29 19:24:01 -04:00
|
|
|
|
2016-12-20 09:26:57 -04:00
|
|
|
if (should_log(MASK_LOG_RC)) {
|
2013-12-29 19:24:01 -04:00
|
|
|
Log_Write_RC();
|
2016-12-20 09:26:57 -04:00
|
|
|
}
|
2016-04-04 20:59:09 -03:00
|
|
|
|
|
|
|
if (should_log(MASK_LOG_IMU)) {
|
|
|
|
DataFlash.Log_Write_Vibration(ins);
|
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2013-07-14 20:57:00 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
update aux servo mappings
|
|
|
|
*/
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::update_aux(void)
|
2013-07-14 20:57:00 -03:00
|
|
|
{
|
2017-01-06 06:31:10 -04:00
|
|
|
SRV_Channels::enable_aux_servos();
|
2013-07-14 20:57:00 -03:00
|
|
|
}
|
|
|
|
|
2013-06-03 21:37:05 -03:00
|
|
|
/*
|
|
|
|
once a second events
|
|
|
|
*/
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::one_second_loop(void)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2016-12-20 09:26:57 -04:00
|
|
|
if (should_log(MASK_LOG_CURRENT)) {
|
2015-05-24 19:59:16 -03:00
|
|
|
Log_Write_Current();
|
2016-12-20 09:26:57 -04:00
|
|
|
}
|
2015-05-24 19:59:16 -03:00
|
|
|
// send a heartbeat
|
|
|
|
gcs_send_message(MSG_HEARTBEAT);
|
2013-06-03 03:53:10 -03:00
|
|
|
|
|
|
|
// allow orientation change at runtime to aid config
|
|
|
|
ahrs.set_orientation();
|
2013-06-03 06:33:59 -03:00
|
|
|
|
|
|
|
set_control_channels();
|
2013-06-03 21:37:05 -03:00
|
|
|
|
|
|
|
// cope with changes to aux functions
|
2013-07-14 20:57:00 -03:00
|
|
|
update_aux();
|
2013-06-03 21:37:05 -03:00
|
|
|
|
2015-10-30 02:56:41 -03:00
|
|
|
// update notify flags
|
|
|
|
AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false);
|
|
|
|
AP_Notify::flags.pre_arm_gps_check = true;
|
|
|
|
AP_Notify::flags.armed = arming.is_armed() || arming.arming_required() == AP_Arming::NO;
|
|
|
|
|
2013-06-03 21:37:05 -03:00
|
|
|
// cope with changes to mavlink system ID
|
|
|
|
mavlink_system.sysid = g.sysid_this_mav;
|
|
|
|
|
2015-05-12 04:00:25 -03:00
|
|
|
static uint8_t counter;
|
2013-06-03 21:37:05 -03:00
|
|
|
|
|
|
|
counter++;
|
|
|
|
|
|
|
|
// write perf data every 20s
|
2013-10-28 03:21:35 -03:00
|
|
|
if (counter % 10 == 0) {
|
|
|
|
if (scheduler.debug() != 0) {
|
2017-02-20 09:26:00 -04:00
|
|
|
hal.console->printf("G_Dt_max=%u\n", G_Dt_max);
|
2013-10-28 03:21:35 -03:00
|
|
|
}
|
2016-12-20 09:26:57 -04:00
|
|
|
if (should_log(MASK_LOG_PM)) {
|
2013-06-03 21:37:05 -03:00
|
|
|
Log_Write_Performance();
|
2016-12-20 09:26:57 -04:00
|
|
|
}
|
2013-11-01 20:40:29 -03:00
|
|
|
G_Dt_max = 0;
|
2013-06-03 21:37:05 -03:00
|
|
|
resetPerfData();
|
|
|
|
}
|
|
|
|
|
|
|
|
// save compass offsets once a minute
|
2015-05-24 19:59:16 -03:00
|
|
|
if (counter >= 60) {
|
2013-06-03 21:37:05 -03:00
|
|
|
if (g.compass_enabled) {
|
|
|
|
compass.save_offsets();
|
|
|
|
}
|
|
|
|
counter = 0;
|
|
|
|
}
|
2015-05-06 23:11:43 -03:00
|
|
|
|
|
|
|
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
|
2016-12-20 09:26:57 -04:00
|
|
|
|
2017-05-04 06:10:05 -03:00
|
|
|
// update home position if not soft armed and gps position has
|
|
|
|
// changed. Update every 1s at most
|
|
|
|
if (!hal.util->get_soft_armed() &&
|
|
|
|
gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
|
|
|
update_home();
|
|
|
|
}
|
|
|
|
|
2016-10-27 23:20:56 -03:00
|
|
|
// update error mask of sensors and subsystems. The mask uses the
|
|
|
|
// MAV_SYS_STATUS_* values from mavlink. If a bit is set then it
|
|
|
|
// indicates that the sensor or subsystem is present but not
|
|
|
|
// functioning correctly
|
|
|
|
update_sensor_status_flags();
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2015-08-06 09:50:52 -03:00
|
|
|
void Rover::dataflash_periodic(void)
|
|
|
|
{
|
|
|
|
DataFlash.periodic_tasks();
|
|
|
|
}
|
|
|
|
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::update_GPS_50Hz(void)
|
2015-05-24 19:59:16 -03:00
|
|
|
{
|
2015-05-12 04:00:25 -03:00
|
|
|
static uint32_t last_gps_reading[GPS_MAX_INSTANCES];
|
2015-05-24 19:59:16 -03:00
|
|
|
gps.update();
|
2013-12-21 07:27:06 -04:00
|
|
|
|
2016-12-20 09:26:57 -04:00
|
|
|
for (uint8_t i=0; i < gps.num_sensors(); i++) {
|
2014-04-09 21:30:15 -03:00
|
|
|
if (gps.last_message_time_ms(i) != last_gps_reading[i]) {
|
|
|
|
last_gps_reading[i] = gps.last_message_time_ms(i);
|
|
|
|
if (should_log(MASK_LOG_GPS)) {
|
2016-05-03 19:26:20 -03:00
|
|
|
DataFlash.Log_Write_GPS(gps, i);
|
2014-04-09 21:30:15 -03:00
|
|
|
}
|
2013-04-28 01:57:19 -03:00
|
|
|
}
|
|
|
|
}
|
2013-12-29 19:33:32 -04:00
|
|
|
}
|
|
|
|
|
2013-04-28 01:57:19 -03:00
|
|
|
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::update_GPS_10Hz(void)
|
2015-05-24 19:59:16 -03:00
|
|
|
{
|
2014-01-02 22:10:52 -04:00
|
|
|
have_position = ahrs.get_position(current_loc);
|
2012-11-28 07:44:03 -04:00
|
|
|
|
2015-10-30 02:20:28 -03:00
|
|
|
if (gps.last_message_time_ms() != last_gps_msg_ms && gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
|
|
|
last_gps_msg_ms = gps.last_message_time_ms();
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2016-12-20 09:26:57 -04:00
|
|
|
if (ground_start_count > 1) {
|
2015-05-24 19:59:16 -03:00
|
|
|
ground_start_count--;
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2015-05-24 19:59:16 -03:00
|
|
|
} else if (ground_start_count == 1) {
|
|
|
|
// We countdown N number of good GPS fixes
|
|
|
|
// so that the altitude is more accurate
|
|
|
|
// -------------------------------------
|
2016-10-03 14:16:23 -03:00
|
|
|
if (current_loc.lat == 0 && current_loc.lng == 0) {
|
2015-05-24 19:59:16 -03:00
|
|
|
ground_start_count = 20;
|
|
|
|
} else {
|
2012-11-17 02:45:20 -04:00
|
|
|
init_home();
|
2013-10-23 09:28:07 -03:00
|
|
|
|
|
|
|
// set system clock for log timestamps
|
2017-01-31 06:12:26 -04:00
|
|
|
const uint64_t gps_timestamp = gps.time_epoch_usec();
|
2016-12-20 09:26:57 -04:00
|
|
|
|
2016-01-21 02:57:52 -04:00
|
|
|
hal.util->set_system_clock(gps_timestamp);
|
2016-12-20 09:26:57 -04:00
|
|
|
|
2016-01-21 02:57:52 -04:00
|
|
|
// update signing timestamp
|
|
|
|
GCS_MAVLINK::update_signing_timestamp(gps_timestamp);
|
2013-10-23 09:28:07 -03:00
|
|
|
|
2015-05-24 19:59:16 -03:00
|
|
|
if (g.compass_enabled) {
|
|
|
|
// Set compass declination automatically
|
|
|
|
compass.set_initial_location(gps.location().lat, gps.location().lng);
|
|
|
|
}
|
|
|
|
ground_start_count = 0;
|
|
|
|
}
|
|
|
|
}
|
2016-05-31 08:23:01 -03:00
|
|
|
// get ground speed estimate from AHRS
|
|
|
|
ground_speed = ahrs.groundspeed();
|
2013-07-14 20:57:00 -03:00
|
|
|
|
|
|
|
#if CAMERA == ENABLED
|
2015-12-18 03:16:11 -04:00
|
|
|
if (camera.update_location(current_loc, rover.ahrs) == true) {
|
2013-07-14 20:57:00 -03:00
|
|
|
do_take_picture();
|
|
|
|
}
|
2015-05-24 19:59:16 -03:00
|
|
|
#endif
|
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::update_current_mode(void)
|
2015-05-24 19:59:16 -03:00
|
|
|
{
|
2017-01-31 05:46:32 -04:00
|
|
|
switch (control_mode) {
|
2012-11-27 18:20:20 -04:00
|
|
|
case AUTO:
|
|
|
|
case RTL:
|
2017-03-15 00:00:14 -03:00
|
|
|
if (!in_auto_reverse) {
|
|
|
|
set_reverse(false);
|
|
|
|
}
|
2017-01-18 13:34:42 -04:00
|
|
|
if (!do_auto_rotation) {
|
|
|
|
calc_lateral_acceleration();
|
|
|
|
calc_nav_steer();
|
|
|
|
calc_throttle(g.speed_cruise);
|
|
|
|
} else {
|
|
|
|
do_yaw_rotation();
|
|
|
|
}
|
2013-03-01 07:32:57 -04:00
|
|
|
break;
|
|
|
|
|
2016-09-15 09:09:45 -03:00
|
|
|
case GUIDED: {
|
2017-03-15 00:00:14 -03:00
|
|
|
if (!in_auto_reverse) {
|
|
|
|
set_reverse(false);
|
|
|
|
}
|
2017-01-31 05:46:32 -04:00
|
|
|
switch (guided_mode) {
|
2016-09-15 09:09:45 -03:00
|
|
|
case Guided_Angle:
|
|
|
|
nav_set_yaw_speed();
|
|
|
|
break;
|
|
|
|
|
|
|
|
case Guided_WP:
|
|
|
|
if (rtl_complete || verify_RTL()) {
|
|
|
|
// we have reached destination so stop where we are
|
2017-01-06 06:31:10 -04:00
|
|
|
if (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) != g.throttle_min.get()) {
|
2016-09-15 09:09:45 -03:00
|
|
|
gcs_send_mission_item_reached_message(0);
|
|
|
|
}
|
2017-01-31 05:46:32 -04:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, g.throttle_min.get());
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, 0);
|
2016-09-15 09:09:45 -03:00
|
|
|
lateral_acceleration = 0;
|
|
|
|
} else {
|
|
|
|
calc_lateral_acceleration();
|
|
|
|
calc_nav_steer();
|
2017-02-15 15:11:08 -04:00
|
|
|
calc_throttle(rover.guided_control.target_speed);
|
2017-05-03 11:21:58 -03:00
|
|
|
Log_Write_GuidedTarget(guided_mode, Vector3f(next_WP.lat, next_WP.lng, next_WP.alt),
|
2017-05-03 11:06:54 -03:00
|
|
|
Vector3f(rover.guided_control.target_speed, SRV_Channels::get_output_scaled(SRV_Channel::k_throttle), 0.0f));
|
2015-12-21 13:48:51 -04:00
|
|
|
}
|
2016-09-15 09:09:45 -03:00
|
|
|
break;
|
|
|
|
|
2017-05-03 11:21:58 -03:00
|
|
|
case Guided_Velocity:
|
|
|
|
nav_set_speed();
|
|
|
|
break;
|
|
|
|
|
2016-09-15 09:09:45 -03:00
|
|
|
default:
|
|
|
|
gcs_send_text(MAV_SEVERITY_WARNING, "Unknown GUIDED mode");
|
|
|
|
break;
|
2015-05-07 21:50:16 -03:00
|
|
|
}
|
|
|
|
break;
|
2016-09-15 09:09:45 -03:00
|
|
|
}
|
2015-05-07 21:50:16 -03:00
|
|
|
|
2013-06-16 20:50:53 -03:00
|
|
|
case STEERING: {
|
2013-03-01 07:32:57 -04:00
|
|
|
/*
|
2013-09-29 20:04:34 -03:00
|
|
|
in steering mode we control lateral acceleration
|
|
|
|
directly. We first calculate the maximum lateral
|
|
|
|
acceleration at full steering lock for this speed. That is
|
|
|
|
V^2/R where R is the radius of turn. We get the radius of
|
|
|
|
turn from half the STEER2SRV_P.
|
2013-03-01 07:32:57 -04:00
|
|
|
*/
|
2013-09-29 20:04:34 -03:00
|
|
|
float max_g_force = ground_speed * ground_speed / steerController.get_turn_radius();
|
|
|
|
|
|
|
|
// constrain to user set TURN_MAX_G
|
|
|
|
max_g_force = constrain_float(max_g_force, 0.1f, g.turn_max_g * GRAVITY_MSS);
|
|
|
|
|
2017-01-07 01:36:16 -04:00
|
|
|
lateral_acceleration = max_g_force * (channel_steer->get_control_in()/4500.0f);
|
2013-03-01 07:32:57 -04:00
|
|
|
calc_nav_steer();
|
|
|
|
|
2013-10-04 18:41:32 -03:00
|
|
|
// and throttle gives speed in proportion to cruise speed, up
|
|
|
|
// to 50% throttle, then uses nudging above that.
|
2017-01-07 01:36:16 -04:00
|
|
|
float target_speed = channel_throttle->get_control_in() * 0.01f * 2 * g.speed_cruise;
|
2013-11-24 20:21:15 -04:00
|
|
|
set_reverse(target_speed < 0);
|
2013-11-17 19:58:22 -04:00
|
|
|
if (in_reverse) {
|
|
|
|
target_speed = constrain_float(target_speed, -g.speed_cruise, 0);
|
|
|
|
} else {
|
|
|
|
target_speed = constrain_float(target_speed, 0, g.speed_cruise);
|
|
|
|
}
|
2013-10-04 18:41:32 -03:00
|
|
|
calc_throttle(target_speed);
|
2012-11-27 18:20:20 -04:00
|
|
|
break;
|
2013-06-16 20:50:53 -03:00
|
|
|
}
|
2012-11-27 18:20:20 -04:00
|
|
|
|
|
|
|
case LEARNING:
|
|
|
|
case MANUAL:
|
2013-03-01 07:32:57 -04:00
|
|
|
/*
|
|
|
|
in both MANUAL and LEARNING we pass through the
|
|
|
|
controls. Setting servo_out here actually doesn't matter, as
|
|
|
|
we set the exact value in set_servos(), but it helps for
|
|
|
|
logging
|
|
|
|
*/
|
2017-01-31 05:46:32 -04:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, channel_throttle->get_control_in());
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, channel_steer->get_control_in());
|
2013-11-17 19:58:22 -04:00
|
|
|
|
|
|
|
// mark us as in_reverse when using a negative throttle to
|
|
|
|
// stop AHRS getting off
|
2017-01-06 06:31:10 -04:00
|
|
|
set_reverse(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) < 0);
|
2013-02-07 18:21:22 -04:00
|
|
|
break;
|
|
|
|
|
2013-03-28 18:53:20 -03:00
|
|
|
case HOLD:
|
|
|
|
// hold position - stop motors and center steering
|
2017-01-31 05:46:32 -04:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0);
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, 0);
|
2017-03-15 00:00:14 -03:00
|
|
|
if (!in_auto_reverse) {
|
|
|
|
set_reverse(false);
|
|
|
|
}
|
2013-03-28 18:53:20 -03:00
|
|
|
break;
|
|
|
|
|
2013-02-07 18:21:22 -04:00
|
|
|
case INITIALISING:
|
2012-11-27 18:20:20 -04:00
|
|
|
break;
|
2015-05-24 19:59:16 -03:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::update_navigation()
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2012-11-29 03:09:05 -04:00
|
|
|
switch (control_mode) {
|
2013-02-07 18:21:22 -04:00
|
|
|
case MANUAL:
|
2013-03-28 18:53:20 -03:00
|
|
|
case HOLD:
|
2013-02-07 18:21:22 -04:00
|
|
|
case LEARNING:
|
2013-03-01 07:32:57 -04:00
|
|
|
case STEERING:
|
2013-02-07 18:21:22 -04:00
|
|
|
case INITIALISING:
|
|
|
|
break;
|
|
|
|
|
2012-11-29 03:09:05 -04:00
|
|
|
case AUTO:
|
2015-05-24 19:59:16 -03:00
|
|
|
mission.update();
|
2017-01-18 13:34:42 -04:00
|
|
|
if (do_auto_rotation) {
|
|
|
|
do_yaw_rotation();
|
|
|
|
}
|
2012-11-29 03:09:05 -04:00
|
|
|
break;
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2012-11-29 03:09:05 -04:00
|
|
|
case RTL:
|
|
|
|
// no loitering around the wp with the rover, goes direct to the wp position
|
2015-05-24 19:59:16 -03:00
|
|
|
if (verify_RTL()) {
|
2017-01-31 05:46:32 -04:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, g.throttle_min.get());
|
2013-03-28 18:53:20 -03:00
|
|
|
set_mode(HOLD);
|
2017-05-03 11:06:38 -03:00
|
|
|
} else {
|
|
|
|
calc_lateral_acceleration();
|
|
|
|
calc_nav_steer();
|
2012-11-29 03:09:05 -04:00
|
|
|
}
|
|
|
|
break;
|
2015-05-07 21:50:16 -03:00
|
|
|
|
|
|
|
case GUIDED:
|
2017-01-31 05:46:32 -04:00
|
|
|
switch (guided_mode) {
|
2016-09-15 09:09:45 -03:00
|
|
|
case Guided_Angle:
|
|
|
|
nav_set_yaw_speed();
|
|
|
|
break;
|
|
|
|
|
|
|
|
case Guided_WP:
|
|
|
|
// no loitering around the wp with the rover, goes direct to the wp position
|
|
|
|
if (rtl_complete || verify_RTL()) {
|
|
|
|
// we have reached destination so stop where we are
|
2017-01-31 05:46:32 -04:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, g.throttle_min.get());
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, 0);
|
2016-09-15 09:09:45 -03:00
|
|
|
lateral_acceleration = 0;
|
2017-05-03 11:06:38 -03:00
|
|
|
} else {
|
|
|
|
calc_lateral_acceleration();
|
|
|
|
calc_nav_steer();
|
2016-09-15 09:09:45 -03:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2017-05-03 11:21:58 -03:00
|
|
|
case Guided_Velocity:
|
|
|
|
nav_set_speed();
|
|
|
|
break;
|
|
|
|
|
2016-09-15 09:09:45 -03:00
|
|
|
default:
|
|
|
|
gcs_send_text(MAV_SEVERITY_WARNING, "Unknown GUIDED mode");
|
|
|
|
break;
|
2015-05-07 21:50:16 -03:00
|
|
|
}
|
|
|
|
break;
|
2015-05-24 19:59:16 -03:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
2016-09-15 09:09:45 -03:00
|
|
|
|
2016-01-19 01:26:14 -04:00
|
|
|
AP_HAL_MAIN_CALLBACKS(&rover);
|