2015-12-30 18:57:56 -04: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/>.
|
|
|
|
*/
|
2017-02-06 15:05:10 -04:00
|
|
|
|
|
|
|
// ArduSub scheduling, originally copied from ArduCopter
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2016-01-14 15:30:56 -04:00
|
|
|
#include "Sub.h"
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2016-01-14 15:30:56 -04:00
|
|
|
#define SCHED_TASK(func, rate_hz, max_time_micros) SCHED_TASK_CLASS(Sub, &sub, func, rate_hz, max_time_micros)
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
scheduler table for fast CPUs - all regular tasks apart from the fast_loop()
|
2016-05-03 00:23:08 -03:00
|
|
|
should be listed here, along with how often they should be called (in hz)
|
|
|
|
and the maximum time they are expected to take (in microseconds)
|
2015-12-30 18:57:56 -04:00
|
|
|
*/
|
2016-01-14 15:30:56 -04:00
|
|
|
const AP_Scheduler::Task Sub::scheduler_tasks[] = {
|
2017-03-09 13:50:58 -04:00
|
|
|
SCHED_TASK(fifty_hz_loop, 50, 75),
|
2020-06-22 17:34:34 -03:00
|
|
|
SCHED_TASK_CLASS(AP_GPS, &sub.gps, update, 50, 200),
|
2015-12-30 18:57:56 -04:00
|
|
|
#if OPTFLOW == ENABLED
|
2018-09-02 09:33:53 -03:00
|
|
|
SCHED_TASK_CLASS(OpticalFlow, &sub.optflow, update, 200, 160),
|
2015-12-30 18:57:56 -04:00
|
|
|
#endif
|
|
|
|
SCHED_TASK(update_batt_compass, 10, 120),
|
2017-02-03 17:33:27 -04:00
|
|
|
SCHED_TASK(read_rangefinder, 20, 100),
|
|
|
|
SCHED_TASK(update_altitude, 10, 100),
|
2015-12-30 18:57:56 -04:00
|
|
|
SCHED_TASK(three_hz_loop, 3, 75),
|
2017-02-03 17:33:27 -04:00
|
|
|
SCHED_TASK(update_turn_counter, 10, 50),
|
2018-02-12 05:38:06 -04:00
|
|
|
SCHED_TASK_CLASS(AP_Baro, &sub.barometer, accumulate, 50, 90),
|
|
|
|
SCHED_TASK_CLASS(AP_Notify, &sub.notify, update, 50, 90),
|
2015-12-30 18:57:56 -04:00
|
|
|
SCHED_TASK(one_hz_loop, 1, 100),
|
2018-11-22 20:38:17 -04:00
|
|
|
SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_receive, 400, 180),
|
2018-12-13 18:40:10 -04:00
|
|
|
SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_send, 400, 550),
|
2019-09-17 00:37:03 -03:00
|
|
|
#if AC_FENCE == ENABLED
|
|
|
|
SCHED_TASK_CLASS(AC_Fence, &sub.fence, update, 10, 100),
|
|
|
|
#endif
|
2020-07-24 14:30:21 -03:00
|
|
|
#if HAL_MOUNT_ENABLED
|
2018-02-12 05:38:06 -04:00
|
|
|
SCHED_TASK_CLASS(AP_Mount, &sub.camera_mount, update, 50, 75),
|
|
|
|
#endif
|
2017-04-13 00:15:51 -03:00
|
|
|
#if CAMERA == ENABLED
|
2020-06-22 17:34:34 -03:00
|
|
|
SCHED_TASK_CLASS(AP_Camera, &sub.camera, update, 50, 75),
|
2017-04-13 00:15:51 -03:00
|
|
|
#endif
|
2015-12-30 18:57:56 -04:00
|
|
|
SCHED_TASK(ten_hz_logging_loop, 10, 350),
|
2017-02-03 00:18:27 -04:00
|
|
|
SCHED_TASK(twentyfive_hz_logging, 25, 110),
|
2019-01-18 00:23:42 -04:00
|
|
|
SCHED_TASK_CLASS(AP_Logger, &sub.logger, periodic_tasks, 400, 300),
|
2018-02-12 05:38:06 -04:00
|
|
|
SCHED_TASK_CLASS(AP_InertialSensor, &sub.ins, periodic, 400, 50),
|
2018-02-12 17:09:47 -04:00
|
|
|
SCHED_TASK_CLASS(AP_Scheduler, &sub.scheduler, update_logging, 0.1, 75),
|
2016-11-25 18:58:31 -04:00
|
|
|
#if RPM_ENABLED == ENABLED
|
2015-12-30 18:57:56 -04:00
|
|
|
SCHED_TASK(rpm_update, 10, 200),
|
2016-11-25 18:58:31 -04:00
|
|
|
#endif
|
2019-03-25 06:25:22 -03:00
|
|
|
SCHED_TASK_CLASS(Compass, &sub.compass, cal_update, 100, 100),
|
2017-02-03 17:33:27 -04:00
|
|
|
SCHED_TASK(terrain_update, 10, 100),
|
2016-11-17 01:12:06 -04:00
|
|
|
#if GRIPPER_ENABLED == ENABLED
|
2018-04-20 09:41:04 -03:00
|
|
|
SCHED_TASK_CLASS(AP_Gripper, &sub.g2.gripper, update, 10, 75),
|
2015-12-30 18:57:56 -04:00
|
|
|
#endif
|
|
|
|
#ifdef USERHOOK_FASTLOOP
|
|
|
|
SCHED_TASK(userhook_FastLoop, 100, 75),
|
|
|
|
#endif
|
|
|
|
#ifdef USERHOOK_50HZLOOP
|
|
|
|
SCHED_TASK(userhook_50Hz, 50, 75),
|
|
|
|
#endif
|
|
|
|
#ifdef USERHOOK_MEDIUMLOOP
|
|
|
|
SCHED_TASK(userhook_MediumLoop, 10, 75),
|
|
|
|
#endif
|
|
|
|
#ifdef USERHOOK_SLOWLOOP
|
|
|
|
SCHED_TASK(userhook_SlowLoop, 3.3, 75),
|
|
|
|
#endif
|
|
|
|
#ifdef USERHOOK_SUPERSLOWLOOP
|
|
|
|
SCHED_TASK(userhook_SuperSlowLoop, 1, 75),
|
|
|
|
#endif
|
2020-07-18 19:01:36 -03:00
|
|
|
SCHED_TASK(read_airspeed, 10, 100),
|
2015-12-30 18:57:56 -04:00
|
|
|
};
|
|
|
|
|
2020-01-16 06:31:00 -04:00
|
|
|
void Sub::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
|
|
|
|
uint8_t &task_count,
|
|
|
|
uint32_t &log_bit)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2020-01-16 06:31:00 -04:00
|
|
|
tasks = &scheduler_tasks[0];
|
|
|
|
task_count = ARRAY_SIZE(scheduler_tasks);
|
|
|
|
log_bit = MASK_LOG_PM;
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
2020-01-16 06:31:00 -04:00
|
|
|
constexpr int8_t Sub::_failsafe_priorities[5];
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// Main loop - 400hz
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::fast_loop()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2017-04-05 16:34:25 -03:00
|
|
|
// update INS immediately to get current gyro data populated
|
|
|
|
ins.update();
|
|
|
|
|
2019-09-23 13:41:30 -03:00
|
|
|
//don't run rate controller in manual or motordetection modes
|
|
|
|
if (control_mode != MANUAL && control_mode != MOTOR_DETECT) {
|
2017-02-03 17:33:27 -04:00
|
|
|
// run low level rate controllers that only require IMU data
|
|
|
|
attitude_control.rate_controller_run();
|
2017-02-03 00:18:27 -04:00
|
|
|
}
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// send outputs to the motors library
|
|
|
|
motors_output();
|
|
|
|
|
2017-04-05 16:34:25 -03:00
|
|
|
// run EKF state estimator (expensive)
|
|
|
|
// --------------------
|
|
|
|
read_AHRS();
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// Inertial Nav
|
|
|
|
// --------------------
|
|
|
|
read_inertia();
|
|
|
|
|
|
|
|
// check if ekf has reset target heading
|
|
|
|
check_ekf_yaw_reset();
|
|
|
|
|
|
|
|
// run the attitude controllers
|
|
|
|
update_flight_mode();
|
|
|
|
|
|
|
|
// update home from EKF if necessary
|
|
|
|
update_home_from_EKF();
|
|
|
|
|
2016-02-24 18:18:48 -04:00
|
|
|
// check if we've reached the surface or bottom
|
|
|
|
update_surface_and_bottom_detector();
|
|
|
|
|
2020-07-24 14:30:21 -03:00
|
|
|
#if HAL_MOUNT_ENABLED
|
2016-01-26 00:18:31 -04:00
|
|
|
// camera mount's fast update
|
|
|
|
camera_mount.update_fast();
|
2017-02-03 00:18:27 -04:00
|
|
|
#endif
|
2016-01-26 00:18:31 -04:00
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// log sensor health
|
|
|
|
if (should_log(MASK_LOG_ANY)) {
|
|
|
|
Log_Sensor_Health();
|
|
|
|
}
|
2020-03-08 08:07:04 -03:00
|
|
|
|
|
|
|
AP_Vehicle::fast_loop();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
2017-03-09 13:50:58 -04:00
|
|
|
// 50 Hz tasks
|
|
|
|
void Sub::fifty_hz_loop()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2017-03-09 13:50:58 -04:00
|
|
|
// check pilot input failsafe
|
2017-04-14 16:58:54 -03:00
|
|
|
failsafe_pilot_input_check();
|
2017-03-09 13:50:58 -04:00
|
|
|
|
2017-03-24 17:30:28 -03:00
|
|
|
failsafe_crash_check();
|
|
|
|
|
2017-04-08 11:36:16 -03:00
|
|
|
failsafe_ekf_check();
|
|
|
|
|
2017-04-15 02:03:56 -03:00
|
|
|
failsafe_sensors_check();
|
|
|
|
|
2017-10-25 22:44:54 -03:00
|
|
|
// Update rc input/output
|
2018-04-26 23:26:38 -03:00
|
|
|
rc().read_input();
|
2017-03-21 16:40:59 -03:00
|
|
|
SRV_Channels::output_ch_all();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// update_batt_compass - read battery and compass
|
|
|
|
// should be called at 10hz
|
2018-06-28 08:09:40 -03:00
|
|
|
void Sub::update_batt_compass()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
// read battery before compass because it may be used for motor interference compensation
|
2018-03-01 14:44:02 -04:00
|
|
|
battery.read();
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2021-07-27 21:27:39 -03:00
|
|
|
if (AP::compass().available()) {
|
2015-12-30 18:57:56 -04:00
|
|
|
// update compass with throttle value - used for compassmot
|
2017-02-03 00:18:27 -04:00
|
|
|
compass.set_throttle(motors.get_throttle());
|
2015-12-30 18:57:56 -04:00
|
|
|
compass.read();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// ten_hz_logging_loop
|
|
|
|
// should be run at 10hz
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::ten_hz_logging_loop()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
// log attitude data if we're not already logging at the higher rate
|
|
|
|
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) {
|
|
|
|
Log_Write_Attitude();
|
2021-01-09 04:07:51 -04:00
|
|
|
ahrs_view.Write_Rate(motors, attitude_control, pos_control);
|
2015-12-30 18:57:56 -04:00
|
|
|
if (should_log(MASK_LOG_PID)) {
|
2019-01-18 00:24:08 -04:00
|
|
|
logger.Write_PID(LOG_PIDR_MSG, attitude_control.get_rate_roll_pid().get_pid_info());
|
|
|
|
logger.Write_PID(LOG_PIDP_MSG, attitude_control.get_rate_pitch_pid().get_pid_info());
|
|
|
|
logger.Write_PID(LOG_PIDY_MSG, attitude_control.get_rate_yaw_pid().get_pid_info());
|
|
|
|
logger.Write_PID(LOG_PIDA_MSG, pos_control.get_accel_z_pid().get_pid_info());
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
if (should_log(MASK_LOG_MOTBATT)) {
|
|
|
|
Log_Write_MotBatt();
|
|
|
|
}
|
|
|
|
if (should_log(MASK_LOG_RCIN)) {
|
2019-01-18 00:24:08 -04:00
|
|
|
logger.Write_RCIN();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
if (should_log(MASK_LOG_RCOUT)) {
|
2019-01-18 00:24:08 -04:00
|
|
|
logger.Write_RCOUT();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
2021-05-25 01:37:33 -03:00
|
|
|
if (should_log(MASK_LOG_NTUN) && (mode_requires_GPS(control_mode) || !mode_has_manual_throttle(control_mode))) {
|
2018-03-01 01:44:04 -04:00
|
|
|
pos_control.write_log();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
if (should_log(MASK_LOG_IMU) || should_log(MASK_LOG_IMU_FAST) || should_log(MASK_LOG_IMU_RAW)) {
|
2021-01-22 01:27:28 -04:00
|
|
|
AP::ins().Write_Vibration();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
2017-02-03 00:18:27 -04:00
|
|
|
if (should_log(MASK_LOG_CTUN)) {
|
|
|
|
attitude_control.control_monitor_log();
|
|
|
|
}
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
2017-02-03 00:18:27 -04:00
|
|
|
// twentyfive_hz_logging_loop
|
|
|
|
// should be run at 25hz
|
|
|
|
void Sub::twentyfive_hz_logging()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
|
|
|
|
Log_Write_Attitude();
|
2021-01-09 04:07:51 -04:00
|
|
|
ahrs_view.Write_Rate(motors, attitude_control, pos_control);
|
2015-12-30 18:57:56 -04:00
|
|
|
if (should_log(MASK_LOG_PID)) {
|
2019-01-18 00:24:08 -04:00
|
|
|
logger.Write_PID(LOG_PIDR_MSG, attitude_control.get_rate_roll_pid().get_pid_info());
|
|
|
|
logger.Write_PID(LOG_PIDP_MSG, attitude_control.get_rate_pitch_pid().get_pid_info());
|
|
|
|
logger.Write_PID(LOG_PIDY_MSG, attitude_control.get_rate_yaw_pid().get_pid_info());
|
|
|
|
logger.Write_PID(LOG_PIDA_MSG, pos_control.get_accel_z_pid().get_pid_info());
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// log IMU data if we're not already logging at the higher rate
|
2017-02-03 00:18:27 -04:00
|
|
|
if (should_log(MASK_LOG_IMU) && !should_log(MASK_LOG_IMU_RAW)) {
|
2021-01-22 01:27:28 -04:00
|
|
|
AP::ins().Write_IMU();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// three_hz_loop - 3.3hz loop
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::three_hz_loop()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2017-03-24 15:37:45 -03:00
|
|
|
leak_detector.update();
|
|
|
|
|
|
|
|
failsafe_leak_check();
|
2016-08-19 14:54:22 -03:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
failsafe_internal_pressure_check();
|
2016-09-03 19:17:34 -03:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
failsafe_internal_temperature_check();
|
2016-09-03 19:17:34 -03:00
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// check if we've lost contact with the ground station
|
|
|
|
failsafe_gcs_check();
|
|
|
|
|
2016-05-03 01:45:37 -03:00
|
|
|
// check if we've lost terrain data
|
|
|
|
failsafe_terrain_check();
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
#if AC_FENCE == ENABLED
|
|
|
|
// check if we have breached a fence
|
|
|
|
fence_check();
|
|
|
|
#endif // AC_FENCE_ENABLED
|
|
|
|
|
2017-03-23 01:13:38 -03:00
|
|
|
ServoRelayEvents.update_events();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// one_hz_loop - runs at 1Hz
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::one_hz_loop()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2017-04-11 00:34:33 -03:00
|
|
|
bool arm_check = arming.pre_arm_checks(false);
|
|
|
|
ap.pre_arm_check = arm_check;
|
|
|
|
AP_Notify::flags.pre_arm_check = arm_check;
|
2017-03-02 16:12:31 -04:00
|
|
|
AP_Notify::flags.pre_arm_gps_check = position_ok();
|
2019-03-01 20:09:25 -04:00
|
|
|
AP_Notify::flags.flying = motors.armed();
|
2017-03-01 00:05:51 -04:00
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
if (should_log(MASK_LOG_ANY)) {
|
2019-10-25 03:07:45 -03:00
|
|
|
Log_Write_Data(LogDataID::AP_STATE, ap.value);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
if (!motors.armed()) {
|
|
|
|
// make it possible to change ahrs orientation at runtime during initial config
|
2019-02-17 00:54:12 -04:00
|
|
|
ahrs.update_orientation();
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2021-09-04 14:12:53 -03:00
|
|
|
motors.update_throttle_range();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// update assigned functions and enable auxiliary servos
|
2017-01-31 13:06:55 -04:00
|
|
|
SRV_Channels::enable_aux_servos();
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// update position controller alt limits
|
|
|
|
update_poscon_alt_max();
|
|
|
|
|
2016-05-03 01:45:37 -03:00
|
|
|
// log terrain data
|
|
|
|
terrain_logging();
|
2018-08-02 00:20:17 -03:00
|
|
|
|
2018-10-19 04:30:11 -03:00
|
|
|
// need to set "likely flying" when armed to allow for compass
|
|
|
|
// learning to run
|
2020-01-06 19:06:25 -04:00
|
|
|
set_likely_flying(hal.util->get_soft_armed());
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
2018-06-28 08:09:40 -03:00
|
|
|
void Sub::read_AHRS()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
// Perform IMU calculations and get attitude info
|
|
|
|
//-----------------------------------------------
|
2017-04-05 16:34:25 -03:00
|
|
|
// <true> tells AHRS to skip INS update as we have already done it in fast_loop()
|
|
|
|
ahrs.update(true);
|
2021-08-26 01:55:18 -03:00
|
|
|
ahrs_view.update();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
2016-05-22 21:50:44 -03:00
|
|
|
// read baro and rangefinder altitude at 10hz
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::update_altitude()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
// read in baro altitude
|
|
|
|
read_barometer();
|
|
|
|
|
|
|
|
if (should_log(MASK_LOG_CTUN)) {
|
|
|
|
Log_Write_Control_Tuning();
|
2020-01-01 16:37:51 -04:00
|
|
|
#if HAL_GYROFFT_ENABLED
|
|
|
|
gyro_fft.write_log_messages();
|
2020-06-09 17:16:15 -03:00
|
|
|
#else
|
|
|
|
write_notch_log_messages();
|
2020-01-01 16:37:51 -04:00
|
|
|
#endif
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-04-14 00:16:57 -03:00
|
|
|
bool Sub::control_check_barometer()
|
|
|
|
{
|
2018-05-07 13:31:35 -03:00
|
|
|
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
2018-04-14 00:16:57 -03:00
|
|
|
if (!ap.depth_sensor_present) { // can't hold depth without a depth sensor
|
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "Depth sensor is not connected.");
|
|
|
|
return false;
|
|
|
|
} else if (failsafe.sensor_health) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "Depth sensor error.");
|
|
|
|
return false;
|
|
|
|
}
|
2018-05-07 13:31:35 -03:00
|
|
|
#endif
|
2018-04-14 00:16:57 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2020-12-06 08:38:12 -04:00
|
|
|
// vehicle specific waypoint info helpers
|
|
|
|
bool Sub::get_wp_distance_m(float &distance) const
|
|
|
|
{
|
|
|
|
// see GCS_MAVLINK_Sub::send_nav_controller_output()
|
|
|
|
distance = sub.wp_nav.get_wp_distance_to_destination() * 0.01;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// vehicle specific waypoint info helpers
|
|
|
|
bool Sub::get_wp_bearing_deg(float &bearing) const
|
|
|
|
{
|
|
|
|
// see GCS_MAVLINK_Sub::send_nav_controller_output()
|
|
|
|
bearing = sub.wp_nav.get_wp_bearing_to_destination() * 0.01;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// vehicle specific waypoint info helpers
|
|
|
|
bool Sub::get_wp_crosstrack_error_m(float &xtrack_error) const
|
|
|
|
{
|
|
|
|
// no crosstrack error reported, see GCS_MAVLINK_Sub::send_nav_controller_output()
|
|
|
|
xtrack_error = 0;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2016-01-14 15:30:56 -04:00
|
|
|
AP_HAL_MAIN_CALLBACKS(&sub);
|