Browse Source

Plane: prevent motor startup on reboot in quadplanes

we need to prevent RC overrides within px4io from running
mission-4.1.18
Andrew Tridgell 9 years ago
parent
commit
76b6cbbda1
  1. 6
      ArduPlane/GCS_Mavlink.cpp
  2. 16
      ArduPlane/px4_mixer.cpp
  3. 1
      ArduPlane/quadplane.h
  4. 15
      ArduPlane/system.cpp

6
ArduPlane/GCS_Mavlink.cpp

@ -1513,11 +1513,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg) @@ -1513,11 +1513,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
break;
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
if (is_equal(packet.param1,1.0f) || is_equal(packet.param1,3.0f)) {
// when packet.param1 == 3 we reboot to hold in bootloader
hal.scheduler->reboot(is_equal(packet.param1,3.0f));
result = MAV_RESULT_ACCEPTED;
}
result = handle_preflight_reboot(packet, plane.quadplane.enable != 0);
break;
case MAV_CMD_DO_LAND_START:

16
ArduPlane/px4_mixer.cpp

@ -355,7 +355,12 @@ bool Plane::setup_failsafe_mixing(void) @@ -355,7 +355,12 @@ bool Plane::setup_failsafe_mixing(void)
}
for (uint8_t i = 0; i < pwm_values.channel_count; i++) {
pwm_values.values[i] = 900;
if (RC_Channel_aux::channel_function(i) >= RC_Channel_aux::k_motor1 &&
RC_Channel_aux::channel_function(i) <= RC_Channel_aux::k_motor8) {
pwm_values.values[i] = quadplane.thr_min_pwm;
} else {
pwm_values.values[i] = 900;
}
}
if (ioctl(px4io_fd, PWM_SERVO_SET_MIN_PWM, (long unsigned int)&pwm_values) != 0) {
hal.console->printf("SET_MIN_PWM failed\n");
@ -363,7 +368,13 @@ bool Plane::setup_failsafe_mixing(void) @@ -363,7 +368,13 @@ bool Plane::setup_failsafe_mixing(void)
}
for (uint8_t i = 0; i < pwm_values.channel_count; i++) {
pwm_values.values[i] = 2100;
if (RC_Channel_aux::channel_function(i) >= RC_Channel_aux::k_motor1 &&
RC_Channel_aux::channel_function(i) <= RC_Channel_aux::k_motor8) {
hal.rcout->write(i, quadplane.thr_min_pwm);
pwm_values.values[i] = quadplane.thr_min_pwm;
} else {
pwm_values.values[i] = 2100;
}
}
if (ioctl(px4io_fd, PWM_SERVO_SET_MAX_PWM, (long unsigned int)&pwm_values) != 0) {
hal.console->printf("SET_MAX_PWM failed\n");
@ -374,7 +385,6 @@ bool Plane::setup_failsafe_mixing(void) @@ -374,7 +385,6 @@ bool Plane::setup_failsafe_mixing(void)
goto failed;
}
// setup for immediate manual control if FMU dies
if (ioctl(px4io_fd, PWM_SERVO_SET_OVERRIDE_IMMEDIATE, 1) != 0) {
hal.console->printf("SET_OVERRIDE_IMMEDIATE failed\n");
goto failed;

1
ArduPlane/quadplane.h

@ -35,6 +35,7 @@ class QuadPlane @@ -35,6 +35,7 @@ class QuadPlane
public:
friend class Plane;
friend class AP_Tuning_Plane;
friend class GCS_MAVLINK_Plane;
QuadPlane(AP_AHRS_NavEKF &_ahrs);

15
ArduPlane/system.cpp

@ -103,13 +103,16 @@ void Plane::init_ardupilot() @@ -103,13 +103,16 @@ void Plane::init_ardupilot()
init_rc_out_main();
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
// this must be before BoardConfig.init() so if
// BRD_SAFETYENABLE==0 then we don't have safety off yet
for (uint8_t tries=0; tries<10; tries++) {
if (setup_failsafe_mixing()) {
break;
if (!quadplane.enable) {
// this must be before BoardConfig.init() so if
// BRD_SAFETYENABLE==0 then we don't have safety off yet. For
// quadplanes we wait till AP_Motors is initialised
for (uint8_t tries=0; tries<10; tries++) {
if (setup_failsafe_mixing()) {
break;
}
hal.scheduler->delay(10);
}
hal.scheduler->delay(10);
}
#endif

Loading…
Cancel
Save