Browse Source

4.0.11 航线部分相机拍照版本

zr-sdk-4.1.16
bin 4 years ago
parent
commit
2c44aabf50
  1. 12
      ArduCopter/Parameters.cpp
  2. 56
      libraries/AP_Camera/AP_Camera.cpp

12
ArduCopter/Parameters.cpp

@ -1678,24 +1678,24 @@ const char* Copter::get_sysid_board_id(void) @@ -1678,24 +1678,24 @@ const char* Copter::get_sysid_board_id(void)
switch (type)
{
case 0:
snprintf(buf, sizeof(buf), "Version: zr-v4.0.10 ,ID: RS100%04d%05d",(int)nameValue1,(int)nameValue2);
snprintf(buf, sizeof(buf), "Version: zr-v4.0.11 ,ID: RS100%04d%05d",(int)nameValue1,(int)nameValue2);
break;
case 1:
snprintf(buf, sizeof(buf), "Version: zr-v4.0.10 ,ID: M660%04d%05d",(int)nameValue1,(int)nameValue2);
snprintf(buf, sizeof(buf), "Version: zr-v4.0.11 ,ID: M660%04d%05d",(int)nameValue1,(int)nameValue2);
break;
case 2:
snprintf(buf, sizeof(buf), "Version: zr-v4.0.10 ,ID: M610%04d%05d",(int)nameValue1,(int)nameValue2);
snprintf(buf, sizeof(buf), "Version: zr-v4.0.11 ,ID: M610%04d%05d",(int)nameValue1,(int)nameValue2);
break;
case 3:
// snprintf(buf, sizeof(buf), "Version: zr-v4.0.10 ,Board ID: ZRZK.20QT2.%d",(int)nameValue2);
snprintf(buf, sizeof(buf), "Version: zr-v4.0.10 ,Board ID: ZRZK.%5s.%03d",name,(int)g.sysid_board_id);
snprintf(buf, sizeof(buf), "Version: zr-v4.0.11 ,Board ID: ZRZK.%5s.%03d",name,(int)g.sysid_board_id);
break;
case 4:
snprintf(buf, sizeof(buf), "Version: zr-v4.0.10 ,Board ID: ZRZK.19QT2.%d",(int)nameValue2);
snprintf(buf, sizeof(buf), "Version: zr-v4.0.11 ,Board ID: ZRZK.19QT2.%d",(int)nameValue2);
break;
case 5:
snprintf(buf, sizeof(buf), "Version: zr-v4.0.10 ,Board ID: %04d%04d",(int)nameValue1,(int)nameValue2);
snprintf(buf, sizeof(buf), "Version: zr-v4.0.11 ,Board ID: %04d%04d",(int)nameValue1,(int)nameValue2);
break;
default:

56
libraries/AP_Camera/AP_Camera.cpp

@ -595,34 +595,34 @@ void AP_Camera::send_camera_zr_status(mavlink_channel_t chan) @@ -595,34 +595,34 @@ void AP_Camera::send_camera_zr_status(mavlink_channel_t chan)
uint8_t feedback_error_fixed = 0;
uint8_t feedback_format = 0;
// struct AP_Camera::Cam_ZR_Info status = {};
static uint8_t last_delt = 0;
static uint8_t delt_cnt = 0;
uint16_t num = camera_state.num[0];
uint16_t delt_pic_num = 0;
if (camera_state.id < 0x10 || (camera_state.id >= 0x50 &&camera_state.id <= 0x5F))
{
for (size_t i = 1; i < 5; i++)
{
delt_pic_num += abs(num - camera_state.num[i]); // 判断各个相机照片数是否相等
}
if(delt_pic_num == 0){
delt_cnt = 0;
last_delt = 0;
}
if(last_delt != delt_pic_num){
delt_cnt+=1;
if(delt_cnt > 5){ // Mavlink一次可能会发两三个chan,取5确保是两次计算差值满足条件
// gcs().send_text(MAV_SEVERITY_INFO, "照片数差异(%d):%d,%d,%d,%d,%d",delt_pic_num,camera_state.num[0],camera_state.num[1],camera_state.num[2],camera_state.num[3],camera_state.num[4]);
if(delt_pic_num > 5){
gcs().send_text(MAV_SEVERITY_CRITICAL, "%d:照片数差异大,总差值:%d",camera_state.num[0],delt_pic_num);
feedback_gimbal = 20;
}else
{
gcs().send_text(MAV_SEVERITY_INFO, "照片数差异(%d):%d",delt_pic_num,camera_state.num[0]);
}
}
}
}
// static uint8_t last_delt = 0;
// static uint8_t delt_cnt = 0;
// uint16_t num = camera_state.num[0];
// uint16_t delt_pic_num = 0;
// if (camera_state.id < 0x10 || (camera_state.id >= 0x50 &&camera_state.id <= 0x5F))
// {
// for (size_t i = 1; i < 5; i++)
// {
// delt_pic_num += abs(num - camera_state.num[i]); // 判断各个相机照片数是否相等
// }
// if(delt_pic_num == 0){
// delt_cnt = 0;
// last_delt = 0;
// }
// if(last_delt != delt_pic_num){
// delt_cnt+=1;
// if(delt_cnt > 5){ // Mavlink一次可能会发两三个chan,取5确保是两次计算差值满足条件
// // gcs().send_text(MAV_SEVERITY_INFO, "照片数差异(%d):%d,%d,%d,%d,%d",delt_pic_num,camera_state.num[0],camera_state.num[1],camera_state.num[2],camera_state.num[3],camera_state.num[4]);
// if(delt_pic_num > 5){
// gcs().send_text(MAV_SEVERITY_CRITICAL, "%d:照片数差异大,总差值:%d",camera_state.num[0],delt_pic_num);
// feedback_gimbal = 20;
// }else
// {
// gcs().send_text(MAV_SEVERITY_INFO, "照片数差异(%d):%d",delt_pic_num,camera_state.num[0]);
// }
// }
// }
// }
mavlink_camera_zr_status_t msg;
memset(&msg, 0, sizeof(msg));
msg.temperature = camera_state.temperature;

Loading…
Cancel
Save