diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index 42b09b072e..ae65594b1a 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -238,7 +238,7 @@ void ModeRTL::loiterathome_start() AP_Camera *camera = AP::camera(); if (camera != nullptr) { - camera->create_new_folder(); + camera->create_new_folder(9); } } diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index 6e9d80e7c8..a3daa9c0b0 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -657,7 +657,7 @@ void AP_Camera::send_camera_zr_status(mavlink_channel_t chan) mavlink_msg_camera_zr_status_send_struct(chan, &msg); } -void AP_Camera::create_new_folder() +void AP_Camera::create_new_folder(uint8_t type) { #if HAL_WITH_UAVCAN uint8_t can_num_drivers = AP::can().get_num_drivers(); @@ -666,7 +666,7 @@ void AP_Camera::create_new_folder() AP_UAVCAN *uavcan = AP_UAVCAN::get_uavcan(i); if (uavcan != nullptr) { - uavcan->set_zr_cam_cmd(camera_state.id, 10, 1, 0, 0, 0); + uavcan->set_zr_cam_cmd(camera_state.id, type, 1, 0, 0, 0); } } diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index 229ae69a7b..3b5cea2fd7 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -74,7 +74,7 @@ public: void notice_send_camera_status_to_gcs(void); void update_zr_camera_version(void); void send_camera_zr_status(mavlink_channel_t chan); - void create_new_folder(); + void create_new_folder(uint8_t type); static const struct AP_Param::GroupInfo var_info[]; void set_image_index(uint16_t photo_index); uint16_t get_image_index(); diff --git a/remote_update.sh b/remote_update.sh new file mode 100755 index 0000000000..ce2cdaecb6 --- /dev/null +++ b/remote_update.sh @@ -0,0 +1,8 @@ +date -R +starttime=`date +'%Y-%m-%d %H:%M:%S'` +git remote update origin -p +endtime=`date +'%Y-%m-%d %H:%M:%S'` +date -R +start_seconds=$(date --date="$starttime" +%s); +end_seconds=$(date --date="$endtime" +%s); +echo "本次运行时间: "$((end_seconds-start_seconds))"s" diff --git a/版本说明.txt b/版本说明.txt new file mode 100644 index 0000000000..181c7eb1ca --- /dev/null +++ b/版本说明.txt @@ -0,0 +1,49 @@ +zr-v4.0: 经过飞行测试,稳定版本 +zr-v4.0-dev: 新添加的功能,并入主分支前先验证 + +zr-v4.0.1: + +zr-dev-4.0.2: NMEA 时间修复,日志目录名 + +v4.0.3: 快速解锁 + +v4.0.4: 分阶段降落,光流门限,限制GPS切换 _nunber_to_switch, + rc1.1 降落倒计时,状态码刷新,测距日志增加,智能电池压差 + rc1.2 降落锁定遥控,初始切定点,提示HOME点更新 + +zr-v4.0.2 + 优化降落锁定 + 优化激光定高 + +zr-v4.0.3 + 合并bin固件 + NMEA时间错误修复 + 日志时间错误修复 + 增加日志数量参数 + +v4.0.5-rc1 + 电池压差问题修复 + 遥控器出错判断,出错只能切RTL + +v4.0.6-x8_camv1 + 添加CAN拍照,飞行测试正常 + 降落bug待修复 + +zr-v4.0.8 + can通信bug修复,经过多台飞机多架次严重无问题 + RC3-增加绕圈飞行支持 + RC4-增加7s电量算法,六轴可通用固件 + RC5-移除不必要的模块,减小体积和内存占用 11.09 + RC6-RC7,增加照片数差异判断,修复照片差一张的误报错 11.12 + RC8 增加默认参数写入,照片差异改成所有相机差值和 + RC9 激光测距死机问题修复,北醒tfmini,超出距离判断问题 + 增加zr-hexa,默认参数写入固件 + +zr-v4.0.9 + RC0 双天线定向试飞成功, + RC1 定向角度offset代码位置修改,根据GPS2状态切换定向 + RC2 自动切换问题修复,增加EFK高切定向,增加RTL遥控器输入控制,定向模式磁力计总是健康 + RC3 RTL落地可控修复 + RC5 遥控器切模式判断,去除油门判断 + RC11 兼容旧版本ID + RC12 到期判断,月份问题修复 \ No newline at end of file