ardupilot/APMrover2/system.cpp

369 lines
9.8 KiB
C++
Raw Normal View History

/*****************************************************************************
The init_ardupilot function processes everything we need for an in - air restart
We will determine later if we are actually on the ground and process a
ground start in that case.
*****************************************************************************/
2015-05-13 00:16:45 -03:00
#include "Rover.h"
static void mavlink_delay_cb_static()
{
rover.mavlink_delay_cb();
}
static void failsafe_check_static()
{
rover.failsafe_check();
}
void Rover::init_ardupilot()
{
2015-01-28 00:56:36 -04:00
// initialise console serial port
serial_manager.init_console();
hal.console->printf("\n\nInit %s"
2017-08-11 00:49:03 -03:00
"\n\nFree RAM: %u\n",
2018-06-13 08:15:29 -03:00
AP::fwversion().fw_string,
2018-05-03 22:20:58 -03:00
(unsigned)hal.util->available_memory());
//
// Check the EEPROM format version before loading any parameters from EEPROM.
//
load_parameters();
2018-02-28 08:23:09 -04:00
#if STATS_ENABLED == ENABLED
// initialise stats module
g2.stats.init();
2018-02-28 08:23:09 -04:00
#endif
2016-05-30 22:43:42 -03:00
gcs().set_dataflash(&DataFlash);
2014-01-19 21:57:59 -04:00
mavlink_system.sysid = g.sysid_this_mav;
2015-01-28 00:56:36 -04:00
// initialise serial ports
serial_manager.init();
// setup first port early to allow BoardConfig to report errors
gcs().chan(0).setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0);
// 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);
BoardConfig.init();
#if HAL_WITH_UAVCAN
BoardConfig_CAN.init();
#endif
// initialise notify system
notify.init(false);
notify_mode(control_mode);
ServoRelayEvents.set_channel_mask(0xFFF0);
battery.init();
rssi.init();
// init baro before we start the GCS, so that the CLI baro test works
barometer.init();
2016-05-16 00:33:43 -03:00
// setup telem slots with serial ports
gcs().setup_uarts(serial_manager);
2015-01-28 00:56:36 -04:00
// setup frsky telemetry
#if FRSKY_TELEM_ENABLED == ENABLED
2018-06-13 08:15:29 -03:00
frsky_telemetry.init(serial_manager, (is_boat() ? MAV_TYPE_SURFACE_BOAT : MAV_TYPE_GROUND_ROVER));
#endif
#if DEVO_TELEM_ENABLED == ENABLED
devo_telemetry.init(serial_manager);
#endif
#if LOGGING_ENABLED == ENABLED
2015-05-13 00:16:45 -03:00
log_init();
#endif
// initialise compass
init_compass();
2017-07-13 08:36:44 -03:00
// initialise rangefinder
init_rangefinder();
2017-08-16 07:57:42 -03:00
// init proximity sensor
init_proximity();
// init beacons used for non-gps position estimation
init_beacon();
2017-06-01 04:39:49 -03:00
// init visual odometry
init_visual_odom();
// and baro for EKF
barometer.set_log_baro_bit(MASK_LOG_IMU);
barometer.calibrate();
// Do GPS init
gps.set_log_gps_bit(MASK_LOG_GPS);
gps.init(serial_manager);
2013-12-21 07:27:06 -04:00
ins.set_log_raw_bit(MASK_LOG_IMU_RAW);
2017-07-10 06:43:55 -03:00
set_control_channels(); // setup radio channels and ouputs ranges
init_rc_in(); // sets up rc channels deadzone
g2.motors.init(); // init motors including setting servo out channels ranges
init_rc_out(); // enable output
2017-07-11 23:02:51 -03:00
// init wheel encoders
g2.wheel_encoder.init();
relay.init();
2015-01-28 00:56:36 -04:00
#if MOUNT == ENABLED
// initialise camera mount
camera_mount.init(serial_manager);
2015-01-28 00:56:36 -04:00
#endif
/*
setup the 'main loop is dead' check. Note that this relies on
the RC library being initialised.
*/
2015-05-12 04:00:25 -03:00
hal.scheduler->register_timer_failsafe(failsafe_check_static, 1000);
// give AHRS the range beacon sensor
ahrs.set_beacon(&g2.beacon);
// initialize SmartRTL
g2.smart_rtl.init();
2015-01-28 00:56:36 -04:00
init_capabilities();
2015-07-31 18:14:51 -03:00
startup_ground();
Mode *initial_mode = mode_from_mode_num((enum Mode::Number)g.initial_mode.get());
2017-07-18 23:19:08 -03:00
if (initial_mode == nullptr) {
initial_mode = &mode_initializing;
}
2017-07-24 14:05:59 -03:00
set_mode(*initial_mode, MODE_REASON_INITIALISED);
2017-07-18 23:19:08 -03:00
// set the correct flight mode
// ---------------------------
reset_control_switch();
init_aux_switch();
// disable safety if requested
BoardConfig.init_safety();
// flag that initialisation has completed
initialised = true;
}
//*********************************************************************************
// This function does all the calibrations, etc. that we need during a ground start
//*********************************************************************************
void Rover::startup_ground(void)
{
2017-07-24 14:05:59 -03:00
set_mode(mode_initializing, MODE_REASON_INITIALISED);
gcs().send_text(MAV_SEVERITY_INFO, "<startup_ground> Ground start");
#if(GROUND_START_DELAY > 0)
gcs().send_text(MAV_SEVERITY_NOTICE, "<startup_ground> With delay");
delay(GROUND_START_DELAY * 1000);
#endif
// IMU ground start
//------------------------
//
startup_INS_ground();
// initialise mission library
mission.init();
// initialise DataFlash library
#if LOGGING_ENABLED == ENABLED
DataFlash.set_mission(&mission);
DataFlash.setVehicle_Startup_Log_Writer(
FUNCTOR_BIND(&rover, &Rover::Log_Write_Vehicle_Startup_Messages, void)
);
#endif
2015-01-28 00:56:36 -04:00
// we don't want writes to the serial port to cause us to pause
// so set serial ports non-blocking once we are ready to drive
serial_manager.set_blocking_writes_all(false);
gcs().send_text(MAV_SEVERITY_INFO, "Ready to drive");
}
// update the ahrs flyforward setting which can allow
// the vehicle's movements to be used to estimate heading
void Rover::update_ahrs_flyforward()
{
bool flyforward = false;
// boats never use movement to estimate heading
if (!is_boat()) {
// throttle threshold is 15% or 1/2 cruise throttle
bool throttle_over_thresh = g2.motors.get_throttle() > MIN(g.throttle_cruise * 0.50f, 15.0f);
// desired speed threshold of 1m/s
bool desired_speed_over_thresh = g2.attitude_control.speed_control_active() && (g2.attitude_control.get_desired_speed() > 0.5f);
if (throttle_over_thresh || (is_positive(g2.motors.get_throttle()) && desired_speed_over_thresh)) {
uint32_t now = AP_HAL::millis();
// if throttle over threshold start timer
if (flyforward_start_ms == 0) {
flyforward_start_ms = now;
}
// if throttle over threshold for 2 seconds set flyforward to true
flyforward = (now - flyforward_start_ms > 2000);
} else {
// reset timer
flyforward_start_ms = 0;
}
}
ahrs.set_fly_forward(flyforward);
}
2017-07-24 14:05:59 -03:00
bool Rover::set_mode(Mode &new_mode, mode_reason_t reason)
{
2017-07-18 23:19:08 -03:00
if (control_mode == &new_mode) {
// don't switch modes if we are already in the correct mode.
2017-07-18 23:19:08 -03:00
return true;
}
2017-07-18 23:19:08 -03:00
Mode &old_mode = *control_mode;
if (!new_mode.enter()) {
2017-07-24 14:05:59 -03:00
// Log error that we failed to enter desired flight mode
Log_Write_Error(ERROR_SUBSYSTEM_FLIGHT_MODE, new_mode.mode_number());
gcs().send_text(MAV_SEVERITY_WARNING, "Flight mode change failed");
2017-07-18 23:19:08 -03:00
return false;
}
2017-07-18 23:19:08 -03:00
control_mode = &new_mode;
2017-08-16 07:02:56 -03:00
// pilot requested flight mode change during a fence breach indicates pilot is attempting to manually recover
// this flight mode change could be automatic (i.e. fence, battery, GPS or GCS failsafe)
// but it should be harmless to disable the fence temporarily in these situations as well
g2.fence.manual_recovery_start();
#if FRSKY_TELEM_ENABLED == ENABLED
2017-07-18 23:19:08 -03:00
frsky_telemetry.update_control_mode(control_mode->mode_number());
#endif
#if DEVO_TELEM_ENABLED == ENABLED
devo_telemetry.update_control_mode(control_mode->mode_number());
#endif
#if CAMERA == ENABLED
camera.set_is_auto_mode(control_mode->mode_number() == Mode::Number::AUTO);
#endif
2017-07-18 23:19:08 -03:00
old_mode.exit();
control_mode_reason = reason;
DataFlash.Log_Write_Mode(control_mode->mode_number(), control_mode_reason);
notify_mode(control_mode);
2017-07-18 23:19:08 -03:00
return true;
}
void Rover::startup_INS_ground(void)
{
gcs().send_text(MAV_SEVERITY_INFO, "Beginning INS calibration. Do not move vehicle");
2017-08-22 06:30:40 -03:00
hal.scheduler->delay(100);
2013-01-13 01:03:54 -04:00
ahrs.init();
// say to EKF that rover only move by goind forward
ahrs.set_fly_forward(true);
2014-04-21 05:11:45 -03:00
ahrs.set_vehicle_class(AHRS_VEHICLE_GROUND);
2013-10-20 19:09:57 -03:00
ins.init(scheduler.get_loop_rate_hz());
ahrs.reset();
}
// update notify with mode change
void Rover::notify_mode(const Mode *mode)
{
notify.flags.flight_mode = mode->mode_number();
notify.set_flight_mode_str(mode->name4());
}
/*
check a digitial pin for high,low (1/0)
*/
uint8_t Rover::check_digital_pin(uint8_t pin)
{
2018-08-01 06:52:54 -03:00
const int8_t dpin = pin;
if (dpin == -1) {
return 0;
}
// ensure we are in input mode
2014-06-01 20:27:52 -03:00
hal.gpio->pinMode(dpin, HAL_GPIO_INPUT);
// enable pullup
hal.gpio->write(dpin, 1);
return hal.gpio->read(dpin);
}
2014-01-14 00:10:13 -04:00
/*
should we log a message type now?
*/
bool Rover::should_log(uint32_t mask)
2014-01-14 00:10:13 -04:00
{
return DataFlash.should_log(mask);
2014-01-14 00:10:13 -04:00
}
/*
update AHRS soft arm state and log as needed
*/
void Rover::change_arm_state(void)
{
Log_Write_Arm_Disarm();
update_soft_armed();
}
/*
arm motors
*/
bool Rover::arm_motors(AP_Arming::ArmingMethod method)
{
if (!arming.arm(method)) {
2017-11-30 23:22:44 -04:00
AP_Notify::events.arming_failed = true;
return false;
}
// Set the SmartRTL home location. If activated, SmartRTL will ultimately try to land at this point
g2.smart_rtl.set_home(true);
change_arm_state();
return true;
}
/*
disarm motors
*/
bool Rover::disarm_motors(void)
{
if (!arming.disarm()) {
return false;
}
2017-07-18 23:19:08 -03:00
if (control_mode != &mode_auto) {
// reset the mission on disarm if we are not in auto
mission.reset();
}
// only log if disarming was successful
change_arm_state();
return true;
}
// returns true if vehicle is a boat
// this affects whether the vehicle tries to maintain position after reaching waypoints
bool Rover::is_boat() const
{
return ((enum frame_class)g2.frame_class.get() == FRAME_BOAT);
}