Browse Source

增加是否启用遥控器判断,auto rtl 模式恢复遥控控制,版本号修改

celiu-4.0.17-rc8
zbr 4 years ago
parent
commit
c909fcb0ba
  1. 9
      ArduCopter/Parameters.cpp
  2. 3
      ArduCopter/Parameters.h
  3. 6
      ArduCopter/mode.cpp
  4. 6
      ArduCopter/mode_auto.cpp
  5. 12
      ArduCopter/mode_rtl.cpp
  6. 6
      ArduCopter/version.h
  7. 3
      zr-v4.sh

9
ArduCopter/Parameters.cpp

@ -141,6 +141,7 @@ const AP_Param::Info Copter::var_info[] = {
// @Increment: 1 // @Increment: 1
// @User: Standard // @User: Standard
GSCALAR(zr_tk_delay, "ZR_TK_DELAY", ZR_TK_DELAY), GSCALAR(zr_tk_delay, "ZR_TK_DELAY", ZR_TK_DELAY),
GSCALAR(zr_use_rc, "ZR_USE_RC", 1),
// @Param: ZR_RTL_DELAY // @Param: ZR_RTL_DELAY
// @DisplayName: rtl Altitude when at final decent alt // @DisplayName: rtl Altitude when at final decent alt
@ -1667,16 +1668,16 @@ const char* Copter::get_sysid_board_id(void)
switch (type) switch (type)
{ {
case 0: case 0:
snprintf(buf, sizeof(buf), "Version: zr-v4.1.1 ,ID: RS100%04d%05d",(int)nameValue1,(int)nameValue2); snprintf(buf, sizeof(buf), "Version: zr-v4.1.2 ,ID: RS100%04d%05d",(int)nameValue1,(int)nameValue2);
break; break;
case 1: case 1:
snprintf(buf, sizeof(buf), "Version: zr-v4.1.1 ,ID: M660%04d%05d",(int)nameValue1,(int)nameValue2); snprintf(buf, sizeof(buf), "Version: zr-v4.1.2 ,ID: M660%04d%05d",(int)nameValue1,(int)nameValue2);
break; break;
case 2: case 2:
snprintf(buf, sizeof(buf), "Version: zr-v4.1.1 ,ID: RF610%04d%05d",(int)nameValue1,(int)nameValue2); snprintf(buf, sizeof(buf), "Version: zr-v4.1.2 ,ID: RF610%04d%05d",(int)nameValue1,(int)nameValue2);
break; break;
case 3: case 3:
snprintf(buf, sizeof(buf), "Version: zr-v4.1.1 ,Board ID: ZRZK.20QT2.%d",(int)nameValue2); snprintf(buf, sizeof(buf), "Version: zr-v4.1.2 ,Board ID: ZRZK.20QT2.%d",(int)nameValue2);
break; break;
default: default:

3
ArduCopter/Parameters.h

@ -390,6 +390,7 @@ public:
k_param_zr_tk_delay, k_param_zr_tk_delay,
k_param_zr_rtl_delay, k_param_zr_rtl_delay,
k_param_zr_send_type, k_param_zr_send_type,
k_param_zr_use_rc,
// the k_param_* space is 9-bits in size // the k_param_* space is 9-bits in size
// 511: reserved // 511: reserved
}; };
@ -502,6 +503,8 @@ public:
AP_Int16 zr_tk_delay; AP_Int16 zr_tk_delay;
AP_Int16 zr_rtl_delay; AP_Int16 zr_rtl_delay;
AP_Int8 zr_send_type; AP_Int8 zr_send_type;
AP_Int8 zr_use_rc;
// Note: keep initializers here in the same order as they are declared // Note: keep initializers here in the same order as they are declared
// above. // above.
Parameters() Parameters()

6
ArduCopter/mode.cpp

@ -606,7 +606,8 @@ void Mode::land_run_horizontal_control()
update_simple_mode(); update_simple_mode();
// convert pilot input to lean angles // 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()); if(g.zr_use_rc)
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 // record if pilot has overridden roll or pitch
if (!is_zero(target_roll) || !is_zero(target_pitch)) { if (!is_zero(target_roll) || !is_zero(target_pitch)) {
@ -618,7 +619,8 @@ void Mode::land_run_horizontal_control()
} }
// get pilot's desired yaw rate // get pilot's desired yaw rate
// target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); if(g.zr_use_rc)
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!is_zero(target_yaw_rate)) { if (!is_zero(target_yaw_rate)) {
auto_yaw.set_mode(AUTO_YAW_HOLD); auto_yaw.set_mode(AUTO_YAW_HOLD);
} }

6
ArduCopter/mode_auto.cpp

@ -807,7 +807,7 @@ void ModeAuto::wp_run()
float target_yaw_rate = 0; float target_yaw_rate = 0;
if (!copter.failsafe.radio) { if (!copter.failsafe.radio) {
// get pilot's desired yaw rate // 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)) { if (!is_zero(target_yaw_rate)) {
auto_yaw.set_mode(AUTO_YAW_HOLD); auto_yaw.set_mode(AUTO_YAW_HOLD);
} }
@ -854,7 +854,7 @@ void ModeAuto::spline_run()
float target_yaw_rate = 0; float target_yaw_rate = 0;
if (!copter.failsafe.radio) { if (!copter.failsafe.radio) {
// get pilot's desired yaw rat // 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)) { if (!is_zero(target_yaw_rate)) {
auto_yaw.set_mode(AUTO_YAW_HOLD); auto_yaw.set_mode(AUTO_YAW_HOLD);
} }
@ -950,7 +950,7 @@ void ModeAuto::loiter_run()
// accept pilot input of yaw // accept pilot input of yaw
float target_yaw_rate = 0; float target_yaw_rate = 0;
if (!copter.failsafe.radio) { 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 // set motors to full range

12
ArduCopter/mode_rtl.cpp

@ -191,7 +191,8 @@ void ModeRTL::climb_return_run()
float target_yaw_rate = 0; float target_yaw_rate = 0;
if (!copter.failsafe.radio) { if (!copter.failsafe.radio) {
// get pilot's desired yaw rate // get pilot's desired yaw rate
// target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); if(g.zr_use_rc)
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!is_zero(target_yaw_rate)) { if (!is_zero(target_yaw_rate)) {
auto_yaw.set_mode(AUTO_YAW_HOLD); auto_yaw.set_mode(AUTO_YAW_HOLD);
} }
@ -248,7 +249,8 @@ void ModeRTL::loiterathome_run()
float target_yaw_rate = 0; float target_yaw_rate = 0;
if (!copter.failsafe.radio) { if (!copter.failsafe.radio) {
// get pilot's desired yaw rate // get pilot's desired yaw rate
// target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); if(g.zr_use_rc)
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!is_zero(target_yaw_rate)) { if (!is_zero(target_yaw_rate)) {
auto_yaw.set_mode(AUTO_YAW_HOLD); auto_yaw.set_mode(AUTO_YAW_HOLD);
} }
@ -333,7 +335,8 @@ void ModeRTL::descent_run()
update_simple_mode(); update_simple_mode();
// convert pilot input to lean angles // 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()); if(g.zr_use_rc)
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 // record if pilot has overridden roll or pitch
if (!is_zero(target_roll) || !is_zero(target_pitch)) { if (!is_zero(target_roll) || !is_zero(target_pitch)) {
@ -345,7 +348,8 @@ void ModeRTL::descent_run()
} }
// get pilot's desired yaw rate // get pilot's desired yaw rate
// target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); if(g.zr_use_rc)
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
} }
// set motors to full range // set motors to full range

6
ArduCopter/version.h

@ -6,12 +6,12 @@
#include "ap_version.h" #include "ap_version.h"
#define THISFIRMWARE "ZRUAV v4.1.1" //"ArduCopter V4.0.0" #define THISFIRMWARE "ZRUAV v4.1.2" //"ArduCopter V4.0.0"
// the following line is parsed by the autotest scripts // the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,1,1,FIRMWARE_VERSION_TYPE_OFFICIAL #define FIRMWARE_VERSION 4,1,2,FIRMWARE_VERSION_TYPE_OFFICIAL
#define FW_MAJOR 4 #define FW_MAJOR 4
#define FW_MINOR 1 #define FW_MINOR 1
#define FW_PATCH 1 #define FW_PATCH 2
#define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL #define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL

3
zr-v4.sh

@ -1,2 +1,3 @@
./waf configure --board zr-v4 ./waf configure --board zr-v4
./waf --targets bin/arducopter --upload ./waf copter
cp ./build/zr-v4/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/zr-v4/wsl/flow-zrv4.px4

Loading…
Cancel
Save