Browse Source

rtl rc disable

master
z 5 years ago
parent
commit
3c55f5276f
  1. 13
      ArduCopter/UserCode.cpp
  2. 4
      ArduCopter/mode.cpp
  3. 6
      ArduCopter/mode_auto.cpp
  4. 8
      ArduCopter/mode_rtl.cpp
  5. 2
      ArduCopter/version.h
  6. 2
      libraries/RC_Channel/RC_Channel.cpp
  7. 16
      libraries/RC_Channel/RC_Channel.h
  8. 2
      zr_version

13
ArduCopter/UserCode.cpp

@ -10,6 +10,7 @@ void Copter::userhook_init() @@ -10,6 +10,7 @@ void Copter::userhook_init()
// this will be called once at start-up
relay.on(1);
set_mode(Mode::Number::LOITER, ModeReason::STARTUP);
}
#endif
@ -85,15 +86,15 @@ void Copter::userhook_SuperSlowLoop() @@ -85,15 +86,15 @@ void Copter::userhook_SuperSlowLoop()
if(motors->armed()){
before_fly = false;
relay.on(3);
if (control_mode == Mode::Number::AUTO || control_mode == Mode::Number::RTL || control_mode == Mode::Number::LAND){
rc().set_disable_ch();
}else{
rc().set_enable_ch();
}
// if (control_mode == Mode::Number::AUTO || control_mode == Mode::Number::RTL || control_mode == Mode::Number::LAND){
// rc().set_disable_ch();
// }else{
// rc().set_enable_ch();
// }
}else{
relay.off(3);
rc().set_enable_ch();
// rc().set_enable_ch();
updownStatus =UpDown_TakeOffStart;
mavlink_zr_flying_status_t zr_flying_status_t;
zr_flying_status_t.updown_status = updownStatus;

4
ArduCopter/mode.cpp

@ -633,8 +633,8 @@ void Mode::land_run_horizontal_control() @@ -633,8 +633,8 @@ void Mode::land_run_horizontal_control()
}
#endif
static uint8_t prt_once;
// bool land_lock_attitude = (get_alt_above_ground_cm() < g.land_lock_alt * 2) && copter.rangefinder_alt_ok() && g.land_lock_alt && (copter.control_mode == Mode::Number::LAND);
bool land_lock_attitude = (get_alt_above_ground_cm() < g.land_lock_alt * 4) && g.land_lock_alt && (copter.control_mode == Mode::Number::LAND);
bool land_lock_attitude = (get_alt_above_ground_cm() < g.land_lock_alt * 2) && copter.rangefinder_alt_ok() && g.land_lock_alt && (copter.control_mode == Mode::Number::LAND);
// bool land_lock_attitude = (get_alt_above_ground_cm() < g.land_lock_alt * 4) && g.land_lock_alt && (copter.control_mode == Mode::Number::LAND);
if(land_lock_attitude)
{
if(prt_once == 0)

6
ArduCopter/mode_auto.cpp

@ -808,7 +808,7 @@ void ModeAuto::wp_run() @@ -808,7 +808,7 @@ void ModeAuto::wp_run()
float target_yaw_rate = 0;
if (!copter.failsafe.radio) {
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
// target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!is_zero(target_yaw_rate)) {
auto_yaw.set_mode(AUTO_YAW_HOLD);
}
@ -855,7 +855,7 @@ void ModeAuto::spline_run() @@ -855,7 +855,7 @@ void ModeAuto::spline_run()
float target_yaw_rate = 0;
if (!copter.failsafe.radio) {
// get pilot's desired yaw rat
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
// target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!is_zero(target_yaw_rate)) {
auto_yaw.set_mode(AUTO_YAW_HOLD);
}
@ -951,7 +951,7 @@ void ModeAuto::loiter_run() @@ -951,7 +951,7 @@ void ModeAuto::loiter_run()
// accept pilot input of yaw
float target_yaw_rate = 0;
if (!copter.failsafe.radio) {
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
// target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
}
// set motors to full range

8
ArduCopter/mode_rtl.cpp

@ -197,7 +197,7 @@ void ModeRTL::climb_return_run() @@ -197,7 +197,7 @@ void ModeRTL::climb_return_run()
float target_yaw_rate = 0;
if (!copter.failsafe.radio) {
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
// target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!is_zero(target_yaw_rate)) {
auto_yaw.set_mode(AUTO_YAW_HOLD);
}
@ -254,7 +254,7 @@ void ModeRTL::loiterathome_run() @@ -254,7 +254,7 @@ void ModeRTL::loiterathome_run()
float target_yaw_rate = 0;
if (!copter.failsafe.radio) {
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
// target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!is_zero(target_yaw_rate)) {
auto_yaw.set_mode(AUTO_YAW_HOLD);
}
@ -342,7 +342,7 @@ void ModeRTL::descent_run() @@ -342,7 +342,7 @@ void ModeRTL::descent_run()
update_simple_mode();
// convert pilot input to lean angles
get_pilot_desired_lean_angles(target_roll, target_pitch, loiter_nav->get_angle_max_cd(), attitude_control->get_althold_lean_angle_max());
// get_pilot_desired_lean_angles(target_roll, target_pitch, loiter_nav->get_angle_max_cd(), attitude_control->get_althold_lean_angle_max());
// record if pilot has overridden roll or pitch
if (!is_zero(target_roll) || !is_zero(target_pitch)) {
@ -354,7 +354,7 @@ void ModeRTL::descent_run() @@ -354,7 +354,7 @@ void ModeRTL::descent_run()
}
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
// target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
}
// set motors to full range

2
ArduCopter/version.h

@ -6,7 +6,7 @@ @@ -6,7 +6,7 @@
#include "ap_version.h"
#define THISFIRMWARE "ZRUAV v4.0.4-rc1.1" //"ArduCopter V4.0.0"
#define THISFIRMWARE "ZRUAV v4.0.4-rc1.2" //"ArduCopter V4.0.0"
// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,0,4,FIRMWARE_VERSION_TYPE_OFFICIAL

2
libraries/RC_Channel/RC_Channel.cpp

@ -136,7 +136,7 @@ RC_Channel::update(void) @@ -136,7 +136,7 @@ RC_Channel::update(void)
if (has_override() && !rc().ignore_overrides()) {
radio_in = override_value;
} else if (!rc().ignore_receiver()) {
if(rc().ignore_ctrl_channel() && !rc().is_enable_ch(ch_in)){
if(rc().ignore_ctrl_channel() && ch_in < 6){
return false;
}else{
radio_in = hal.rcin->read(ch_in);

16
libraries/RC_Channel/RC_Channel.h

@ -343,16 +343,16 @@ public: @@ -343,16 +343,16 @@ public:
return _options & uint32_t(Option::IGNORE_CTRLCHAN);
}
bool is_enable_ch(uint8_t ch) const {
return (_enable_ch == (ch+1) );
bool is_enable_ch(uint8_t num) const {
return (_enable_ch == (num+1) );
}
void set_disable_ch() {
_options = uint32_t(Option::IGNORE_CTRLCHAN);
}
void set_enable_ch() {
_options = 0;
}
// void set_disable_ch() {
// _options = uint32_t(Option::IGNORE_CTRLCHAN);
// }
// void set_enable_ch() {
// _options = 0;
// }
float override_timeout_ms() const {
return _override_timeout.get() * 1e3f;

2
zr_version

@ -9,7 +9,7 @@ v4.0.3: 快速解锁 @@ -9,7 +9,7 @@ v4.0.3: 快速解锁
v4.0.4: 分阶段降落,光流门限,限制GPS切换 _nunber_to_switch,
rc1.1 降落倒计时,状态码刷新,测距日志增加,智能电池压差
rc1.2 降落锁定遥控,初始切定点,提示HOME点更新

Loading…
Cancel
Save