mirror of https://github.com/ArduPilot/ardupilot
193 lines
6.0 KiB
C++
193 lines
6.0 KiB
C++
#include "Sub.h"
|
|
|
|
// enable_motor_output() - enable and output lowest possible value to motors
|
|
void Sub::enable_motor_output()
|
|
{
|
|
// enable motors
|
|
motors.enable();
|
|
motors.output_min();
|
|
}
|
|
|
|
// init_arm_motors - performs arming process including initialisation of barometer and gyros
|
|
// returns false if arming failed because of pre-arm checks, arming checks or a gyro calibration failure
|
|
bool Sub::init_arm_motors(bool arming_from_gcs)
|
|
{
|
|
start_logging();
|
|
static bool in_arm_motors = false;
|
|
|
|
// exit immediately if already in this function
|
|
if (in_arm_motors) {
|
|
return false;
|
|
}
|
|
|
|
in_arm_motors = true;
|
|
|
|
if (!arming.pre_arm_checks(true)) {
|
|
AP_Notify::events.arming_failed = true;
|
|
in_arm_motors = false;
|
|
return false;
|
|
}
|
|
|
|
// let dataflash know that we're armed (it may open logs e.g.)
|
|
DataFlash_Class::instance()->set_vehicle_armed(true);
|
|
|
|
// disable cpu failsafe because initialising everything takes a while
|
|
mainloop_failsafe_disable();
|
|
|
|
// notify that arming will occur (we do this early to give plenty of warning)
|
|
AP_Notify::flags.armed = true;
|
|
// call update_notify a few times to ensure the message gets out
|
|
for (uint8_t i=0; i<=10; i++) {
|
|
update_notify();
|
|
}
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
gcs_send_text(MAV_SEVERITY_INFO, "Arming motors");
|
|
#endif
|
|
|
|
initial_armed_bearing = ahrs.yaw_sensor;
|
|
|
|
if (ap.home_state == HOME_UNSET) {
|
|
// Reset EKF altitude if home hasn't been set yet (we use EKF altitude as substitute for alt above home)
|
|
|
|
// Always use absolute altitude for ROV
|
|
// ahrs.resetHeightDatum();
|
|
// Log_Write_Event(DATA_EKF_ALT_RESET);
|
|
} else if (ap.home_state == HOME_SET_NOT_LOCKED) {
|
|
// Reset home position if it has already been set before (but not locked)
|
|
set_home_to_current_location();
|
|
}
|
|
|
|
// enable gps velocity based centrefugal force compensation
|
|
ahrs.set_correct_centrifugal(true);
|
|
hal.util->set_soft_armed(true);
|
|
|
|
// enable output to motors
|
|
enable_motor_output();
|
|
|
|
// finally actually arm the motors
|
|
motors.armed(true);
|
|
|
|
// log arming to dataflash
|
|
Log_Write_Event(DATA_ARMED);
|
|
|
|
// log flight mode in case it was changed while vehicle was disarmed
|
|
DataFlash.Log_Write_Mode(control_mode, control_mode_reason);
|
|
|
|
// reenable failsafe
|
|
mainloop_failsafe_enable();
|
|
|
|
// perf monitor ignores delay due to arming
|
|
perf_ignore_this_loop();
|
|
|
|
// flag exiting this function
|
|
in_arm_motors = false;
|
|
|
|
// return success
|
|
return true;
|
|
}
|
|
|
|
// init_disarm_motors - disarm motors
|
|
void Sub::init_disarm_motors()
|
|
{
|
|
// return immediately if we are already disarmed
|
|
if (!motors.armed()) {
|
|
return;
|
|
}
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
gcs_send_text(MAV_SEVERITY_INFO, "Disarming motors");
|
|
#endif
|
|
|
|
// save compass offsets learned by the EKF if enabled
|
|
if (ahrs.use_compass() && compass.get_learn_type() == Compass::LEARN_EKF) {
|
|
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
|
|
Vector3f magOffsets;
|
|
if (ahrs.getMagOffsets(i, magOffsets)) {
|
|
compass.set_and_save_offsets(i, magOffsets);
|
|
}
|
|
}
|
|
}
|
|
|
|
// log disarm to the dataflash
|
|
Log_Write_Event(DATA_DISARMED);
|
|
|
|
// send disarm command to motors
|
|
motors.armed(false);
|
|
|
|
// reset the mission
|
|
mission.reset();
|
|
|
|
DataFlash_Class::instance()->set_vehicle_armed(false);
|
|
|
|
if (DataFlash.log_while_disarmed()) {
|
|
start_logging(); // create a new log if necessary
|
|
} else {
|
|
DataFlash.EnableWrites(false); // suspend logging
|
|
}
|
|
|
|
// disable gps velocity based centrefugal force compensation
|
|
ahrs.set_correct_centrifugal(false);
|
|
hal.util->set_soft_armed(false);
|
|
}
|
|
|
|
// motors_output - send output to motors library which will adjust and send to ESCs and servos
|
|
void Sub::motors_output()
|
|
{
|
|
// check if we are performing the motor test
|
|
if (ap.motor_test) {
|
|
return; // Placeholder
|
|
}
|
|
motors.set_interlock(true);
|
|
motors.output();
|
|
}
|
|
|
|
// translate wpnav roll/pitch outputs to lateral/forward
|
|
void Sub::translate_wpnav_rp(float &lateral_out, float &forward_out)
|
|
{
|
|
// get roll and pitch targets in centidegrees
|
|
int32_t lateral = wp_nav.get_roll();
|
|
int32_t forward = -wp_nav.get_pitch(); // output is reversed
|
|
|
|
// constrain target forward/lateral values
|
|
// The outputs of wp_nav.get_roll and get_pitch should already be constrained to these values
|
|
lateral = constrain_int16(lateral, -aparm.angle_max, aparm.angle_max);
|
|
forward = constrain_int16(forward, -aparm.angle_max, aparm.angle_max);
|
|
|
|
// Normalize
|
|
lateral_out = (float)lateral/(float)aparm.angle_max;
|
|
forward_out = (float)forward/(float)aparm.angle_max;
|
|
}
|
|
|
|
// translate wpnav roll/pitch outputs to lateral/forward
|
|
void Sub::translate_circle_nav_rp(float &lateral_out, float &forward_out)
|
|
{
|
|
// get roll and pitch targets in centidegrees
|
|
int32_t lateral = circle_nav.get_roll();
|
|
int32_t forward = -circle_nav.get_pitch(); // output is reversed
|
|
|
|
// constrain target forward/lateral values
|
|
lateral = constrain_int16(lateral, -aparm.angle_max, aparm.angle_max);
|
|
forward = constrain_int16(forward, -aparm.angle_max, aparm.angle_max);
|
|
|
|
// Normalize
|
|
lateral_out = (float)lateral/(float)aparm.angle_max;
|
|
forward_out = (float)forward/(float)aparm.angle_max;
|
|
}
|
|
|
|
// translate pos_control roll/pitch outputs to lateral/forward
|
|
void Sub::translate_pos_control_rp(float &lateral_out, float &forward_out)
|
|
{
|
|
// get roll and pitch targets in centidegrees
|
|
int32_t lateral = pos_control.get_roll();
|
|
int32_t forward = -pos_control.get_pitch(); // output is reversed
|
|
|
|
// constrain target forward/lateral values
|
|
lateral = constrain_int16(lateral, -aparm.angle_max, aparm.angle_max);
|
|
forward = constrain_int16(forward, -aparm.angle_max, aparm.angle_max);
|
|
|
|
// Normalize
|
|
lateral_out = (float)lateral/(float)aparm.angle_max;
|
|
forward_out = (float)forward/(float)aparm.angle_max;
|
|
}
|