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
|
|
|
|
|
|
|
/*
|
2018-04-02 08:47:34 -03:00
|
|
|
scheduler table - all regular tasks are listed here, along with how
|
|
|
|
often they should be called (in Hz) 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[] = {
|
2017-06-19 12:55:14 -03:00
|
|
|
// Function name, Hz, us,
|
2018-04-02 08:47:34 -03:00
|
|
|
SCHED_TASK(read_radio, 50, 200),
|
2018-08-25 03:26:22 -03:00
|
|
|
SCHED_TASK(ahrs_update, 400, 400),
|
2018-04-02 08:47:34 -03:00
|
|
|
SCHED_TASK(read_rangefinders, 50, 200),
|
2018-08-25 03:26:22 -03:00
|
|
|
SCHED_TASK(update_current_mode, 400, 200),
|
|
|
|
SCHED_TASK(set_servos, 400, 200),
|
2018-05-23 02:35:37 -03:00
|
|
|
SCHED_TASK(update_GPS, 50, 300),
|
2018-04-11 09:47:18 -03:00
|
|
|
SCHED_TASK_CLASS(AP_Baro, &rover.barometer, update, 10, 200),
|
2018-04-02 08:47:34 -03:00
|
|
|
SCHED_TASK_CLASS(AP_Beacon, &rover.g2.beacon, update, 50, 200),
|
|
|
|
SCHED_TASK_CLASS(AP_Proximity, &rover.g2.proximity, update, 50, 200),
|
2018-09-26 09:30:59 -03:00
|
|
|
SCHED_TASK_CLASS(AP_WindVane, &rover.g2.windvane, update, 20, 100),
|
2018-04-06 09:16:35 -03:00
|
|
|
#if VISUAL_ODOMETRY_ENABLED == ENABLED
|
|
|
|
SCHED_TASK_CLASS(AP_VisualOdom, &rover.g2.visual_odom, update, 50, 200),
|
|
|
|
#endif
|
2018-08-07 23:38:55 -03:00
|
|
|
SCHED_TASK(update_wheel_encoder, 50, 200),
|
2018-04-02 08:47:34 -03:00
|
|
|
SCHED_TASK(update_compass, 10, 200),
|
|
|
|
SCHED_TASK(update_mission, 50, 200),
|
|
|
|
SCHED_TASK(update_logging1, 10, 200),
|
|
|
|
SCHED_TASK(update_logging2, 10, 200),
|
2018-12-06 18:59:25 -04:00
|
|
|
SCHED_TASK_CLASS(GCS, (GCS*)&rover._gcs, update_receive, 400, 500),
|
|
|
|
SCHED_TASK_CLASS(GCS, (GCS*)&rover._gcs, update_send, 400, 1000),
|
2018-11-21 23:54:25 -04:00
|
|
|
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&rover.g2.rc_channels, read_mode_switch, 7, 200),
|
|
|
|
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&rover.g2.rc_channels, read_aux_all, 10, 200),
|
2018-04-02 08:47:34 -03:00
|
|
|
SCHED_TASK_CLASS(AP_BattMonitor, &rover.battery, read, 10, 300),
|
|
|
|
SCHED_TASK_CLASS(AP_ServoRelayEvents, &rover.ServoRelayEvents, update_events, 50, 200),
|
2019-02-07 19:45:23 -04:00
|
|
|
#if GRIPPER_ENABLED == ENABLED
|
|
|
|
SCHED_TASK_CLASS(AP_Gripper, &rover.g2.gripper, update, 10, 75),
|
|
|
|
#endif
|
2018-12-30 16:43:39 -04:00
|
|
|
SCHED_TASK(rpm_update, 10, 100),
|
2018-02-12 01:24:29 -04:00
|
|
|
#if MOUNT == ENABLED
|
2018-04-02 08:47:34 -03:00
|
|
|
SCHED_TASK_CLASS(AP_Mount, &rover.camera_mount, update, 50, 200),
|
2018-02-12 01:24:29 -04:00
|
|
|
#endif
|
|
|
|
#if CAMERA == ENABLED
|
2018-04-02 08:47:34 -03:00
|
|
|
SCHED_TASK_CLASS(AP_Camera, &rover.camera, update_trigger, 50, 200),
|
2018-02-12 01:24:29 -04:00
|
|
|
#endif
|
2018-04-02 08:47:34 -03:00
|
|
|
SCHED_TASK(gcs_failsafe_check, 10, 200),
|
|
|
|
SCHED_TASK(fence_check, 10, 200),
|
2018-11-01 04:04:58 -03:00
|
|
|
SCHED_TASK(ekf_check, 10, 100),
|
2018-04-02 08:47:34 -03:00
|
|
|
SCHED_TASK_CLASS(ModeSmartRTL, &rover.mode_smartrtl, save_position, 3, 200),
|
2018-02-12 01:24:29 -04:00
|
|
|
SCHED_TASK_CLASS(AP_Notify, &rover.notify, update, 50, 300),
|
2018-04-02 08:47:34 -03:00
|
|
|
SCHED_TASK(one_second_loop, 1, 1500),
|
2018-08-25 03:26:22 -03:00
|
|
|
SCHED_TASK_CLASS(AC_Sprayer, &rover.g2.sprayer, update, 3, 90),
|
2018-04-02 08:47:34 -03:00
|
|
|
SCHED_TASK(compass_cal_update, 50, 200),
|
2018-06-18 00:21:04 -03:00
|
|
|
SCHED_TASK(compass_save, 0.1, 200),
|
2018-04-02 08:47:34 -03:00
|
|
|
SCHED_TASK(accel_cal_update, 10, 200),
|
2018-04-20 05:57:14 -03:00
|
|
|
#if LOGGING_ENABLED == ENABLED
|
2019-01-18 00:23:42 -04:00
|
|
|
SCHED_TASK_CLASS(AP_Logger, &rover.logger, periodic_tasks, 50, 300),
|
2018-04-20 05:57:14 -03:00
|
|
|
#endif
|
2018-08-25 03:26:22 -03:00
|
|
|
SCHED_TASK_CLASS(AP_InertialSensor, &rover.ins, periodic, 400, 200),
|
2018-04-02 08:47:34 -03:00
|
|
|
SCHED_TASK_CLASS(AP_Scheduler, &rover.scheduler, update_logging, 0.1, 200),
|
|
|
|
SCHED_TASK_CLASS(AP_Button, &rover.button, update, 5, 200),
|
2018-02-28 08:23:09 -04:00
|
|
|
#if STATS_ENABLED == ENABLED
|
2018-04-02 08:47:34 -03:00
|
|
|
SCHED_TASK(stats_update, 1, 200),
|
2018-02-28 08:23:09 -04:00
|
|
|
#endif
|
2018-04-02 08:47:34 -03:00
|
|
|
SCHED_TASK(crash_check, 10, 200),
|
|
|
|
SCHED_TASK(cruise_learn_update, 50, 200),
|
2017-01-30 10:21:55 -04:00
|
|
|
#if ADVANCED_FAILSAFE == ENABLED
|
2018-04-02 08:47:34 -03:00
|
|
|
SCHED_TASK(afs_fs_check, 10, 200),
|
2017-01-30 10:21:55 -04:00
|
|
|
#endif
|
2018-09-14 04:09:07 -03:00
|
|
|
SCHED_TASK(read_airspeed, 10, 100),
|
2015-05-12 04:00:25 -03:00
|
|
|
};
|
|
|
|
|
2018-03-01 23:30:40 -04:00
|
|
|
constexpr int8_t Rover::_failsafe_priorities[7];
|
|
|
|
|
2018-02-28 08:23:09 -04:00
|
|
|
#if STATS_ENABLED == ENABLED
|
2016-10-25 23:19:28 -03:00
|
|
|
/*
|
|
|
|
update AP_Stats
|
|
|
|
*/
|
|
|
|
void Rover::stats_update(void)
|
|
|
|
{
|
2018-06-06 03:18:24 -03:00
|
|
|
g2.stats.set_flying(g2.motors.active());
|
2016-10-25 23:19:28 -03:00
|
|
|
g2.stats.update();
|
|
|
|
}
|
2018-02-28 08:23:09 -04:00
|
|
|
#endif
|
2016-10-25 23:19:28 -03:00
|
|
|
|
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 16:17:17 -04:00
|
|
|
// load the default values of variables listed in var_info[]
|
|
|
|
AP_Param::setup_sketch_defaults();
|
|
|
|
|
2015-03-02 01:57:36 -04:00
|
|
|
init_ardupilot();
|
2013-06-03 21:37:05 -03:00
|
|
|
|
|
|
|
// initialise the main loop scheduler
|
2018-02-09 18:36:36 -04:00
|
|
|
scheduler.init(&scheduler_tasks[0], ARRAY_SIZE(scheduler_tasks), MASK_LOG_PM);
|
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
|
|
|
{
|
2017-11-13 03:53:39 -04:00
|
|
|
scheduler.loop();
|
2018-02-13 01:47:15 -04:00
|
|
|
G_Dt = scheduler.get_last_loop_time_s();
|
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);
|
2019-01-18 00:23:42 -04:00
|
|
|
logger.set_vehicle_armed(hal.util->get_soft_armed());
|
2016-07-28 04:31:58 -03:00
|
|
|
}
|
|
|
|
|
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
|
2018-11-21 23:16:39 -04:00
|
|
|
gcs().update();
|
2013-10-27 20:33:52 -03:00
|
|
|
#endif
|
2013-02-28 16:40:47 -04:00
|
|
|
|
2018-05-28 02:15:36 -03:00
|
|
|
// AHRS may use movement to calculate heading
|
|
|
|
update_ahrs_flyforward();
|
2013-11-17 19:58:22 -04:00
|
|
|
|
2013-10-27 20:33:52 -03:00
|
|
|
ahrs.update();
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2018-05-23 02:34:47 -03:00
|
|
|
// update position
|
|
|
|
have_position = ahrs.get_position(current_loc);
|
|
|
|
|
2018-11-07 18:41:48 -04:00
|
|
|
// set home from EKF if necessary and possible
|
|
|
|
if (!ahrs.home_is_set()) {
|
2018-05-29 21:52:57 -03:00
|
|
|
if (!set_home_to_current_location(false)) {
|
|
|
|
// ignore this failure
|
|
|
|
}
|
2018-11-07 18:41:48 -04:00
|
|
|
}
|
2017-06-05 04:55:24 -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);
|
2017-08-02 23:06:39 -03:00
|
|
|
} else if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
|
|
|
ground_speed = ahrs.groundspeed();
|
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();
|
2018-09-25 10:09:47 -03:00
|
|
|
Log_Write_Sail();
|
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)) {
|
2019-01-18 00:24:08 -04:00
|
|
|
logger.Write_IMU();
|
2015-07-13 08:34:58 -03:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
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
|
|
|
{
|
2018-10-31 02:27:56 -03:00
|
|
|
if (!g.fs_gcs_enabled) {
|
|
|
|
// gcs failsafe disabled
|
|
|
|
return;
|
2013-09-15 19:23:21 -03:00
|
|
|
}
|
2018-10-31 02:27:56 -03:00
|
|
|
|
|
|
|
// check for updates from GCS within 2 seconds
|
|
|
|
failsafe_trigger(FAILSAFE_EVENT_GCS, failsafe.last_heartbeat_ms != 0 && (millis() - failsafe.last_heartbeat_ms) > 2000);
|
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();
|
2018-09-25 10:09:47 -03:00
|
|
|
Log_Write_Sail();
|
2016-12-20 09:26:57 -04:00
|
|
|
}
|
2015-05-24 19:59:16 -03:00
|
|
|
|
2017-12-07 08:42:06 -04:00
|
|
|
if (should_log(MASK_LOG_THR)) {
|
|
|
|
Log_Write_Throttle();
|
2019-01-18 00:24:08 -04:00
|
|
|
logger.Write_Beacon(g2.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
|
|
|
}
|
2018-12-10 02:25:25 -04:00
|
|
|
|
|
|
|
if (should_log(MASK_LOG_RANGEFINDER)) {
|
2019-01-18 00:24:08 -04:00
|
|
|
logger.Write_Proximity(g2.proximity);
|
2018-12-10 02:25:25 -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)) {
|
2017-12-07 21:59:52 -04:00
|
|
|
Log_Write_Steering();
|
2013-12-15 20:14:58 -04:00
|
|
|
}
|
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();
|
2019-02-05 01:00:15 -04:00
|
|
|
g2.wheel_encoder.Log_Write();
|
2016-12-20 09:26:57 -04:00
|
|
|
}
|
2016-04-04 20:59:09 -03:00
|
|
|
|
|
|
|
if (should_log(MASK_LOG_IMU)) {
|
2019-01-18 00:24:08 -04:00
|
|
|
logger.Write_Vibration();
|
2016-04-04 20:59:09 -03:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
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
|
|
|
{
|
2015-05-24 19:59:16 -03:00
|
|
|
// send a heartbeat
|
2017-07-07 22:16:56 -03:00
|
|
|
gcs().send_message(MSG_HEARTBEAT);
|
2013-06-03 03:53:10 -03:00
|
|
|
|
|
|
|
// allow orientation change at runtime to aid config
|
2019-02-17 00:53:44 -04:00
|
|
|
ahrs.update_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
|
2018-11-21 18:09:33 -04:00
|
|
|
SRV_Channels::enable_aux_servos();
|
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;
|
2019-03-07 00:02:01 -04:00
|
|
|
AP_Notify::flags.armed = arming.is_armed() || arming.arming_required() == AP_Arming::Required::NO;
|
2019-03-01 02:33:00 -04:00
|
|
|
AP_Notify::flags.flying = hal.util->get_soft_armed();
|
2015-10-30 02:56:41 -03:00
|
|
|
|
2013-06-03 21:37:05 -03:00
|
|
|
// cope with changes to mavlink system ID
|
|
|
|
mavlink_system.sysid = g.sysid_this_mav;
|
|
|
|
|
2018-11-07 18:41:48 -04:00
|
|
|
// attempt to update home position and baro calibration if not armed:
|
|
|
|
if (!hal.util->get_soft_armed()) {
|
2017-05-04 06:10:05 -03:00
|
|
|
update_home();
|
|
|
|
}
|
|
|
|
|
2018-08-02 00:19:20 -03:00
|
|
|
// init compass location for declination
|
|
|
|
init_compass_location();
|
|
|
|
|
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
|
2019-02-13 21:59:27 -04:00
|
|
|
gcs().update_sensor_status_flags();
|
2018-10-19 02:36:07 -03:00
|
|
|
|
|
|
|
// need to set "likely flying" when armed to allow for compass
|
|
|
|
// learning to run
|
|
|
|
ahrs.set_likely_flying(hal.util->get_soft_armed());
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2018-05-23 02:35:37 -03:00
|
|
|
void Rover::update_GPS(void)
|
2015-05-24 19:59:16 -03:00
|
|
|
{
|
2018-05-23 02:35:37 -03:00
|
|
|
gps.update();
|
2017-06-05 04:55:24 -03:00
|
|
|
if (gps.last_message_time_ms() != last_gps_msg_ms) {
|
2015-10-30 02:20:28 -03:00
|
|
|
last_gps_msg_ms = gps.last_message_time_ms();
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2013-07-14 20:57:00 -03:00
|
|
|
#if CAMERA == ENABLED
|
2017-08-03 06:41:21 -03:00
|
|
|
camera.update();
|
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
|
|
|
{
|
2019-01-25 14:58:50 -04:00
|
|
|
// check for emergency stop
|
|
|
|
if (SRV_Channels::get_emergency_stop()) {
|
|
|
|
// relax controllers, motor stopping done at output level
|
|
|
|
g2.attitude_control.relax_I();
|
|
|
|
}
|
|
|
|
|
2017-07-18 23:19:08 -03:00
|
|
|
control_mode->update();
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2019-03-15 22:04:01 -03:00
|
|
|
// update mission including starting or stopping commands. called by scheduler at 10Hz
|
|
|
|
void Rover::update_mission(void)
|
|
|
|
{
|
|
|
|
if (control_mode == &mode_auto) {
|
|
|
|
if (ahrs.home_is_set() && mode_auto.mission.num_commands() > 1) {
|
|
|
|
mode_auto.mission.update();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-01-19 01:26:14 -04:00
|
|
|
AP_HAL_MAIN_CALLBACKS(&rover);
|