mirror of https://github.com/ArduPilot/ardupilot
Blimp: Fix inverted throttle
This commit is contained in:
parent
81650d34a3
commit
de0dcdd9e4
|
@ -107,7 +107,7 @@ bool AP_Arming_Blimp::parameter_checks(bool display_failure)
|
|||
// failsafe parameter checks
|
||||
if (blimp.g.failsafe_throttle) {
|
||||
// check throttle min is above throttle failsafe trigger and that the trigger is above ppm encoder's loss-of-signal value of 900
|
||||
if (blimp.channel_down->get_radio_min() <= blimp.g.failsafe_throttle_value+10 || blimp.g.failsafe_throttle_value < 910) {
|
||||
if (blimp.channel_up->get_radio_min() <= blimp.g.failsafe_throttle_value+10 || blimp.g.failsafe_throttle_value < 910) {
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check FS_THR_VALUE");
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -111,7 +111,7 @@ private:
|
|||
// primary input control channels
|
||||
RC_Channel *channel_right;
|
||||
RC_Channel *channel_front;
|
||||
RC_Channel *channel_down;
|
||||
RC_Channel *channel_up;
|
||||
RC_Channel *channel_yaw;
|
||||
|
||||
AP_Logger logger;
|
||||
|
|
|
@ -106,7 +106,7 @@ bool RC_Channel_Blimp::do_aux_function(const aux_func_t ch_option, const AuxSwit
|
|||
case AUX_FUNC::SAVE_TRIM:
|
||||
if ((ch_flag == AuxSwitchPos::HIGH) &&
|
||||
(blimp.control_mode <= Mode::Number::MANUAL) &&
|
||||
(blimp.channel_down->get_control_in() == 0)) {
|
||||
(blimp.channel_up->get_control_in() == 0)) {
|
||||
blimp.save_trim();
|
||||
}
|
||||
break;
|
||||
|
|
|
@ -19,7 +19,7 @@ Mode::Mode(void) :
|
|||
loiter(blimp.loiter),
|
||||
channel_right(blimp.channel_right),
|
||||
channel_front(blimp.channel_front),
|
||||
channel_down(blimp.channel_down),
|
||||
channel_up(blimp.channel_up),
|
||||
channel_yaw(blimp.channel_yaw),
|
||||
G_Dt(blimp.G_Dt)
|
||||
{ };
|
||||
|
|
|
@ -108,7 +108,7 @@ protected:
|
|||
Loiter *&loiter;
|
||||
RC_Channel *&channel_right;
|
||||
RC_Channel *&channel_front;
|
||||
RC_Channel *&channel_down;
|
||||
RC_Channel *&channel_up;
|
||||
RC_Channel *&channel_yaw;
|
||||
float &G_Dt;
|
||||
|
||||
|
|
|
@ -18,7 +18,7 @@ void Blimp::arm_motors_check()
|
|||
}
|
||||
|
||||
// ensure throttle is down
|
||||
if (channel_down->get_control_in() > 0) { //MIR what dow we do with this?
|
||||
if (channel_up->get_control_in() > 0) { //MIR what dow we do with this?
|
||||
arming_counter = 0;
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -8,23 +8,23 @@ void Blimp::default_dead_zones()
|
|||
{
|
||||
channel_right->set_default_dead_zone(20);
|
||||
channel_front->set_default_dead_zone(20);
|
||||
channel_down->set_default_dead_zone(30);
|
||||
channel_up->set_default_dead_zone(30);
|
||||
channel_yaw->set_default_dead_zone(20);
|
||||
rc().channel(CH_6)->set_default_dead_zone(0);
|
||||
}
|
||||
|
||||
void Blimp::init_rc_in()
|
||||
{
|
||||
channel_right = rc().channel(rcmap.roll()-1);
|
||||
channel_front = rc().channel(rcmap.pitch()-1);
|
||||
channel_down = rc().channel(rcmap.throttle()-1);
|
||||
channel_yaw = rc().channel(rcmap.yaw()-1);
|
||||
channel_right = rc().channel(rcmap.roll()-1);
|
||||
channel_front = rc().channel(rcmap.pitch()-1);
|
||||
channel_up = rc().channel(rcmap.throttle()-1);
|
||||
channel_yaw = rc().channel(rcmap.yaw()-1);
|
||||
|
||||
// set rc channel ranges
|
||||
channel_right->set_angle(RC_SCALE);
|
||||
channel_front->set_angle(RC_SCALE);
|
||||
channel_yaw->set_angle(RC_SCALE);
|
||||
channel_down->set_angle(RC_SCALE);
|
||||
channel_up->set_angle(RC_SCALE);
|
||||
|
||||
// set default dead zones
|
||||
default_dead_zones();
|
||||
|
@ -58,14 +58,14 @@ void Blimp::read_radio()
|
|||
if (rc().read_input()) {
|
||||
ap.new_radio_frame = true;
|
||||
|
||||
set_throttle_and_failsafe(channel_down->get_radio_in());
|
||||
set_throttle_zero_flag(channel_down->get_control_in());
|
||||
set_throttle_and_failsafe(channel_up->get_radio_in());
|
||||
set_throttle_zero_flag(channel_up->get_control_in());
|
||||
|
||||
// RC receiver must be attached if we've just got input
|
||||
ap.rc_receiver_present = true;
|
||||
|
||||
const float dt = (tnow_ms - last_radio_update_ms)*1.0e-3f;
|
||||
rc_throttle_control_in_filter.apply(channel_down->get_control_in(), dt);
|
||||
rc_throttle_control_in_filter.apply(channel_up->get_control_in(), dt);
|
||||
last_radio_update_ms = tnow_ms;
|
||||
return;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue