From 99321f6952241521800e802f3c1f8f144c037046 Mon Sep 17 00:00:00 2001 From: nagezeng Date: Fri, 10 Jun 2022 10:36:07 +0800 Subject: [PATCH] =?UTF-8?q?=E4=BB=BF=E7=BA=BF=E6=A8=A1=E5=BC=8F=E7=A6=81?= =?UTF-8?q?=E7=94=A8=E9=81=A5=E6=8E=A7=E5=81=8F=E8=88=AA=E6=8E=A7=E5=88=B6?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ArduCopter/mode_auto.cpp | 4 ++-- ArduCopter/mode_guided.cpp | 8 ++++---- libraries/AC_ZR_APP/AC_ZR_Serial_API.cpp | 16 ++++++++-------- libraries/AC_ZR_APP/AC_ZR_Serial_API.h | 2 +- 4 files changed, 15 insertions(+), 15 deletions(-) diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index c0484ed8c8..e6e32eb07c 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -888,7 +888,7 @@ void ModeAuto::wp_run() } // process pilot's yaw input float target_yaw_rate = 0; - if (!copter.failsafe.radio) { + if (!copter.failsafe.radio && copter.zr_serial_api.data_trans_init) { //copter.zr_serial_api.data_trans_init 仿线模式启动,禁用遥控控制 // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); if (!is_zero(target_yaw_rate)) { @@ -935,7 +935,7 @@ void ModeAuto::spline_run() // process pilot's yaw input float target_yaw_rate = 0; - if (!copter.failsafe.radio) { + if (!copter.failsafe.radio && copter.zr_serial_api.data_trans_init) { //copter.zr_serial_api.data_trans_init 仿线模式启动,禁用遥控控制 // get pilot's desired yaw rat target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); if (!is_zero(target_yaw_rate)) { diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 1b5fc8a0c7..67da2c9f75 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -386,7 +386,7 @@ void Mode::auto_takeoff_run() // process pilot's yaw input float target_yaw_rate = 0; - if (!copter.failsafe.radio) { + if (!copter.failsafe.radio && copter.zr_serial_api.data_trans_init) { //copter.zr_serial_api.data_trans_init 仿线模式启动,禁用遥控控制 // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); } @@ -417,7 +417,7 @@ void ModeGuided::pos_control_run() { // process pilot's yaw input float target_yaw_rate = 0; - if (!copter.failsafe.radio) { + if (!copter.failsafe.radio && copter.zr_serial_api.data_trans_init) { //copter.zr_serial_api.data_trans_init 仿线模式启动,禁用遥控控制 // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); if (!is_zero(target_yaw_rate)) { @@ -459,7 +459,7 @@ void ModeGuided::vel_control_run() { // process pilot's yaw input float target_yaw_rate = 0; - if (!copter.failsafe.radio) { + if (!copter.failsafe.radio && copter.zr_serial_api.data_trans_init) { //copter.zr_serial_api.data_trans_init 仿线模式启动,禁用遥控控制 // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); if (!is_zero(target_yaw_rate)) { @@ -512,7 +512,7 @@ void ModeGuided::posvel_control_run() // process pilot's yaw input float target_yaw_rate = 0; - if (!copter.failsafe.radio) { + if (!copter.failsafe.radio && copter.zr_serial_api.data_trans_init) { //copter.zr_serial_api.data_trans_init 仿线模式启动,禁用遥控控制 // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); if (!is_zero(target_yaw_rate)) { diff --git a/libraries/AC_ZR_APP/AC_ZR_Serial_API.cpp b/libraries/AC_ZR_APP/AC_ZR_Serial_API.cpp index fca40332cf..d97bc08cd4 100644 --- a/libraries/AC_ZR_APP/AC_ZR_Serial_API.cpp +++ b/libraries/AC_ZR_APP/AC_ZR_Serial_API.cpp @@ -301,14 +301,14 @@ bool AC_ZR_Serial_API::get_control_data(uint8_t mode, ZR_Msg_Type &type,Vector3l if(control_data_last_time == last_time){ // 数据没更新,直接退出 return false; } - AP::logger().Write("DATR", "TimeUS,Mode,Type,X,Y,Z,Yaw", "QBBB", - AP_HAL::micros64(), - mode, - flight_control_parser.msg.type, - flight_control_parser.msg.x, - flight_control_parser.msg.y, - flight_control_parser.msg.z, - flight_control_parser.msg.yaw); + AP::logger().Write("APID", "TimeUS,Mode,Type,X,Y,Z,Yaw", "QBBiiif", + AP_HAL::micros64(), //Q + mode, //B + flight_control_parser.msg.type, //B + flight_control_parser.msg.x, //i + flight_control_parser.msg.y, //i + flight_control_parser.msg.z, //i + flight_control_parser.msg.yaw); //f last_time = control_data_last_time; WITH_SEMAPHORE(sem); diff --git a/libraries/AC_ZR_APP/AC_ZR_Serial_API.h b/libraries/AC_ZR_APP/AC_ZR_Serial_API.h index 4ecf5d53d4..921e705d43 100644 --- a/libraries/AC_ZR_APP/AC_ZR_Serial_API.h +++ b/libraries/AC_ZR_APP/AC_ZR_Serial_API.h @@ -83,7 +83,7 @@ public: uint8_t get_param_debug(){ return parm_msg_debug; }; void print_data(const char *fmt, ...) const; void print_msg(const char *msg) const; - + static const struct AP_Param::GroupInfo var_info[]; protected: AP_Int8 parm_msg_debug;