Browse Source

t提示消息调整

celiu-4.0.17-rc8
zbr 3 years ago
parent
commit
a86fe6d496
  1. 33
      ArduCopter/UserCode.cpp

33
ArduCopter/UserCode.cpp

@ -72,7 +72,7 @@ if(avoid.get_zr_mode() > 0 && (control_mode == Mode::Number::BRAKE || control_mo
} }
} }
} }
if(last_flag != enable_avoid){ if(avoid.get_zr_mode() > 0 && last_flag != enable_avoid){
if(enable_avoid){ if(enable_avoid){
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: 开启自动避障!"); gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: 开启自动避障!");
}else{ }else{
@ -110,7 +110,6 @@ void Copter::userhook_SuperSlowLoop()
}else{ }else{
zr_set_uav_state_to_uavcan(); zr_set_uav_state_to_uavcan();
zr_camera_mkdir(); zr_camera_mkdir();
zr_camera_mkdir();
if(current_loc.alt < avoid.get_zr_avd_alt()){ // 飞行高度小于避障启用高度 if(current_loc.alt < avoid.get_zr_avd_alt()){ // 飞行高度小于避障启用高度
if(home_distance() < abs(avoid.get_zr_avd_on_dist())){ // 距离Home点小于启用距离 if(home_distance() < abs(avoid.get_zr_avd_on_dist())){ // 距离Home点小于启用距离
far_from_home = false; far_from_home = false;
@ -152,13 +151,13 @@ void Copter::userhook_auxSwitch1(uint8_t ch_flag)
// relay.on(2); // relay.on(2);
flow_start_sw = true; flow_start_sw = true;
gcs().send_text(MAV_SEVERITY_NOTICE, "[NOTE]开启手动测流"); gcs().send_text(MAV_SEVERITY_NOTICE, "NOTICE:开启手动测流");
break; break;
} }
case 0: { case 0: {
// relay.off(2); // relay.off(2);
flow_start_sw = false; flow_start_sw = false;
gcs().send_text(MAV_SEVERITY_NOTICE, "[NOTE]关闭手动测流"); gcs().send_text(MAV_SEVERITY_NOTICE, "NOTICE:关闭手动测流");
break; break;
} }
} }
@ -173,26 +172,6 @@ void Copter::userhook_auxSwitch1(uint8_t ch_flag)
// break; // break;
// } // }
// } // }
switch (ch_flag) {
case 2: {
// relay.on(2);
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: debug mode 2!");
in_debug_mode = 1;
break;
}
// case 1: {
// // relay.on(2);
// gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: debug mode 1!");
// in_debug_mode = 1;
// break;
// }
case 0: {
// relay.off(2);
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: debug mode off!");
in_debug_mode = 0;
break;
}
}
#if CAM_DEBUG #if CAM_DEBUG
switch (ch_flag) { switch (ch_flag) {
case 2: { case 2: {
@ -226,13 +205,13 @@ void Copter::userhook_auxSwitch2(uint8_t ch_flag)
case 2: { case 2: {
// relay.on(2); // relay.on(2);
flow_index_sw = true; flow_index_sw = true;
gcs().send_text(MAV_SEVERITY_NOTICE, "[NOTE]测流序号递增"); gcs().send_text(MAV_SEVERITY_NOTICE, "NOTICE:测流序号递增");
break; break;
} }
case 0: { case 0: {
// relay.off(2); // relay.off(2);
flow_index_sw = false; flow_index_sw = false;
gcs().send_text(MAV_SEVERITY_NOTICE, "[NOTE]测流序号不变"); gcs().send_text(MAV_SEVERITY_NOTICE, "NOTICE:测流序号不变");
break; break;
} }
} }
@ -331,7 +310,7 @@ void Copter::zr_mission_flow_mode()
int32_t real_alt; int32_t real_alt;
flow_measure.set_radar_mode(g.zr_flow_type); //设置雷达模式,单测流或者三合一等 flow_measure.set_radar_mode(g.zr_flow_type); //设置雷达模式,单测流或者三合一等
flow_measure.set_radar_sens(g.zr_flow_sens); //设置雷达灵敏度 flow_measure.set_radar_sens(g.zr_flow_sens); //设置雷达灵敏度
flow_measure.set_radar_debug(g.zr_flow_debug); //设置雷达debug模式 // flow_measure.set_radar_debug(g.zr_flow_debug); //设置雷达debug模式
if(g.zr_flow_type == 2) // 单测流+指定水位高 if(g.zr_flow_type == 2) // 单测流+指定水位高
real_alt = g.zr_flow_real_elevation; // 直接设置水位高度 real_alt = g.zr_flow_real_elevation; // 直接设置水位高度

Loading…
Cancel
Save