Browse Source

仿线模式禁用遥控偏航控制

zr-sdk-4.3.1
nagezeng 3 years ago
parent
commit
99321f6952
  1. 4
      ArduCopter/mode_auto.cpp
  2. 8
      ArduCopter/mode_guided.cpp
  3. 16
      libraries/AC_ZR_APP/AC_ZR_Serial_API.cpp

4
ArduCopter/mode_auto.cpp

@ -888,7 +888,7 @@ void ModeAuto::wp_run() @@ -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() @@ -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)) {

8
ArduCopter/mode_guided.cpp

@ -386,7 +386,7 @@ void Mode::auto_takeoff_run() @@ -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() @@ -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() @@ -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() @@ -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)) {

16
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 @@ -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);

Loading…
Cancel
Save