Browse Source

六轴使能遥控器RTL阶段控制

mission-4.1.18
zbr 4 years ago
parent
commit
76ab50e8a0
  1. 9
      ArduCopter/Parameters.cpp
  2. 4
      ArduCopter/mode.cpp
  3. 10
      ArduCopter/mode_rtl.cpp
  4. 6
      ArduCopter/version.h
  5. 7
      ArduCopter/zr_flight.cpp
  6. 4
      hexa-zrv4.sh
  7. 16
      libraries/AP_HAL_ChibiOS/hwdef/zr-hexa/defaults.parm

9
ArduCopter/Parameters.cpp

@ -1665,22 +1665,21 @@ const char* Copter::get_sysid_board_id(void) @@ -1665,22 +1665,21 @@ const char* Copter::get_sysid_board_id(void)
switch (type)
{
case 0:
snprintf(buf, sizeof(buf), "Version: zr-v4.0.8 ,ID: RS100%04d%05d",(int)nameValue1,(int)nameValue2);
snprintf(buf, sizeof(buf), "Version: zr-v4.0.9 ,ID: RS100%04d%05d",(int)nameValue1,(int)nameValue2);
break;
case 1:
snprintf(buf, sizeof(buf), "Version: zr-v4.0.8 ,ID: M660%04d%05d",(int)nameValue1,(int)nameValue2);
snprintf(buf, sizeof(buf), "Version: zr-v4.0.9 ,ID: M660%04d%05d",(int)nameValue1,(int)nameValue2);
break;
case 2:
snprintf(buf, sizeof(buf), "Version: zr-v4.0.8 ,ID: M610%04d%05d",(int)nameValue1,(int)nameValue2);
snprintf(buf, sizeof(buf), "Version: zr-v4.0.9 ,ID: M610%04d%05d",(int)nameValue1,(int)nameValue2);
break;
case 3:
snprintf(buf, sizeof(buf), "Version: zr-v4.0.8 ,Board ID: ZRZK.20QT2.%d",(int)nameValue2);
snprintf(buf, sizeof(buf), "Version: zr-v4.0.9 ,Board ID: ZRZK.20QT2.%d",(int)nameValue2);
break;
default:
break;
}
AP::logger().Write_Message(buf);
return buf;
}

4
ArduCopter/mode.cpp

@ -609,7 +609,7 @@ void Mode::land_run_horizontal_control() @@ -609,7 +609,7 @@ void Mode::land_run_horizontal_control()
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)) {
@ -621,7 +621,7 @@ void Mode::land_run_horizontal_control() @@ -621,7 +621,7 @@ void Mode::land_run_horizontal_control()
}
// 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);
}

10
ArduCopter/mode_rtl.cpp

@ -60,7 +60,7 @@ void ModeRTL::run(bool disarm_on_land) @@ -60,7 +60,7 @@ void ModeRTL::run(bool disarm_on_land)
break;
case RTL_LoiterAtHome:
// if (rtl_path.land || copter.failsafe.radio) {
if (g.rtl_alt_final == 0) {
if (g.rtl_alt_final <= 0) {
land_start();
}else{
descent_start();
@ -192,7 +192,7 @@ void ModeRTL::climb_return_run() @@ -192,7 +192,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);
}
@ -249,7 +249,7 @@ void ModeRTL::loiterathome_run() @@ -249,7 +249,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);
}
@ -334,7 +334,7 @@ void ModeRTL::descent_run() @@ -334,7 +334,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)) {
@ -346,7 +346,7 @@ void ModeRTL::descent_run() @@ -346,7 +346,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

6
ArduCopter/version.h

@ -6,12 +6,12 @@ @@ -6,12 +6,12 @@
#include "ap_version.h"
#define THISFIRMWARE "ZRUAV v4.0.8-RC9" //"ArduCopter V4.0.0"
#define THISFIRMWARE "ZRUAV v4.0.9-RC10" //"ArduCopter V4.0.0"
// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,0,8,FIRMWARE_VERSION_TYPE_OFFICIAL
#define FIRMWARE_VERSION 4,0,9,FIRMWARE_VERSION_TYPE_OFFICIAL
#define FW_MAJOR 4
#define FW_MINOR 0
#define FW_PATCH 8
#define FW_PATCH 9
#define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL

7
ArduCopter/zr_flight.cpp

@ -25,9 +25,7 @@ bool Copter::zr_radio_valid(){ @@ -25,9 +25,7 @@ bool Copter::zr_radio_valid(){
if (!rc().ignore_ctrl_channel() && (control_mode == Mode::Number::AUTO || control_mode == Mode::Number::RTL || control_mode == Mode::Number::LAND)){
if(abs(channel_roll->get_control_in())>750 || \
abs(channel_pitch->get_control_in())>750 || \
abs(channel_yaw->get_control_in())>750 || \
channel_throttle->get_control_in()<380 || \
channel_throttle->get_control_in()>590 )
abs(channel_yaw->get_control_in())>750)
{
// rc().set_disable_ch();
gcs().send_text(MAV_SEVERITY_INFO,"注意遥控通道是否在中位");
@ -103,8 +101,10 @@ void Copter::zr_SuperSlowLoop(){ @@ -103,8 +101,10 @@ void Copter::zr_SuperSlowLoop(){
if(before_fly){
before_fly = false;
camera.create_new_folder();
gcs().send_text(MAV_SEVERITY_INFO,"%s",get_sysid_board_id());
}
relay.on(3);
gcs().send_message(MSG_ZR_FLYING_STATUS);
// camera.set_in_arm_mode(true);
}else{
@ -138,7 +138,6 @@ void Copter::zr_SuperSlowLoop(){ @@ -138,7 +138,6 @@ void Copter::zr_SuperSlowLoop(){
}
}
gcs().send_message(MSG_ZR_FLYING_STATUS);
}
#endif

4
hexa-zrv4.sh

@ -1,3 +1,3 @@ @@ -1,3 +1,3 @@
./waf configure --board zr-hexa
./waf --targets bin/arducopter --upload
cp ./build/zr-hexa/bin/arducopter.apj /mnt/f/_01-work/100=data/固件/zr-v4/dev-六轴_v4.0.8-rc8.px4
./waf copter
cp ./build/zr-hexa/bin/arducopter.apj /mnt/f/_01-work/100=data/固件/zr-v4/六轴_v4.0.9-rc10.px4

16
libraries/AP_HAL_ChibiOS/hwdef/zr-hexa/defaults.parm

@ -71,7 +71,7 @@ BATT_MONITOR 4 @@ -71,7 +71,7 @@ BATT_MONITOR 4
BATT_SERIAL_NUM -1
BATT_VOLT_PIN 0
BRD_BOOT_DELAY 1000
BRD_BOOT_DELAY 2000
BRD_PWM_COUNT 0
BRD_RTC_TYPES 1
BRD_RTC_TZ_MIN 0
@ -99,7 +99,19 @@ CAM_SERVO_ON 1900 @@ -99,7 +99,19 @@ CAM_SERVO_ON 1900
CAM_TRIGG_DIST 0
CAM_TRIGG_TYPE 1
CAM_TYPE 0
CAN_D1_PROTOCOL 1
CAN_D1_UC_ESC_BM 0
CAN_D1_UC_NODE 10
CAN_D1_UC_SRV_BM 0
CAN_D1_UC_SRV_RT 50
CAN_D2_PROTOCOL 1
CAN_P1_BITRATE 1000000
CAN_P1_DRIVER 1
CAN_P2_BITRATE 1000000
CAN_P2_DRIVER 1
CAN_SLCAN_CPORT 0
CAN_SLCAN_SERNUM -1
CAN_SLCAN_TIMOUT 0
CHUTE_ENABLED 0
CIRCLE_RADIUS 1000
CIRCLE_RATE 20

Loading…
Cancel
Save