diff --git a/.gitignore b/.gitignore index 69211d5..b15ebf5 100644 --- a/.gitignore +++ b/.gitignore @@ -1,4 +1,5 @@ cmake-build-debug +build .idea tools/TrainCNN/.idea tools/TrainCNN/__pycache__ \ No newline at end of file diff --git a/CMakeLists.txt b/CMakeLists.txt index 9663ec0..ed47e05 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,4 +1,4 @@ -CMAKE_MINIMUM_REQUIRED(VERSION 3.5) +CMAKE_MINIMUM_REQUIRED(VERSION 3.5) PROJECT(AutoAim) SET(CMAKE_CXX_STANDARD 11) @@ -11,6 +11,8 @@ SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DPATH=\"\\\"${PROJECT_SOURCE_DIR}\\\"\" ## 固定使用相机运行 #SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DRUN_WITH_CAMERA") +SET(BIN_NAME "run") + FIND_PROGRAM(CCACHE_FOUND ccache) IF(CCACHE_FOUND) SET_PROPERTY(GLOBAL PROPERTY RULE_LAUNCH_COMPILE ccache) @@ -19,21 +21,16 @@ IF(CCACHE_FOUND) ENDIF() FIND_PACKAGE(OpenCV 3 REQUIRED) -FIND_PACKAGE(Eigen3 REQUIRED) FIND_PACKAGE(Threads) -INCLUDE_DIRECTORIES(${EIGEN3_INCLUDE_DIR}) +INCLUDE_DIRECTORIES("C:\\Applications\\eigen3") INCLUDE_DIRECTORIES(${PROJECT_SOURCE_DIR}/energy/include) INCLUDE_DIRECTORIES(${PROJECT_SOURCE_DIR}/armor/include) INCLUDE_DIRECTORIES(${PROJECT_SOURCE_DIR}/others/include) FILE(GLOB_RECURSE sourcefiles "others/src/*.cpp" "energy/src/*cpp" "armor/src/*.cpp") -ADD_EXECUTABLE(run main.cpp ${sourcefiles} ) +ADD_EXECUTABLE(${BIN_NAME} main.cpp ${sourcefiles} ) -TARGET_LINK_LIBRARIES(run ${CMAKE_THREAD_LIBS_INIT}) -TARGET_LINK_LIBRARIES(run ${OpenCV_LIBS}) -TARGET_LINK_LIBRARIES(run ${PROJECT_SOURCE_DIR}/others/libMVSDK.so) - -ADD_CUSTOM_TARGET(train COMMAND "gnome-terminal" "-x" "bash" "-c" "\"${PROJECT_SOURCE_DIR}/tools/TrainCNN/backward.py\"" ) - -ADD_CUSTOM_TARGET(bind-monitor COMMAND "${PROJECT_SOURCE_DIR}/tools/bind-monitor.sh" "${PROJECT_SOURCE_DIR}" "${CMAKE_BINARY_DIR}") +TARGET_LINK_LIBRARIES(${BIN_NAME} ${CMAKE_THREAD_LIBS_INIT}) +TARGET_LINK_LIBRARIES(${BIN_NAME} ${OpenCV_LIBS}) +TARGET_LINK_LIBRARIES(${BIN_NAME} "C:/Program\ Files\ (x86)/MindVision/SDK/X64/MVCAMSDK_X64.lib") diff --git a/armor/include/armor_finder/armor_finder.h b/armor/include/armor_finder/armor_finder.h index 0d30ef9..f4dbae2 100644 --- a/armor/include/armor_finder/armor_finder.h +++ b/armor/include/armor_finder/armor_finder.h @@ -7,7 +7,7 @@ #include #include -#include +#include #include typedef enum{ @@ -16,7 +16,7 @@ typedef enum{ class ArmorFinder{ public: - ArmorFinder(EnemyColor color, Uart &u, string paras_folder, const bool &use); + ArmorFinder(EnemyColor &color, Serial &u, string paras_folder, const bool &use); ~ArmorFinder() = default; private: @@ -26,7 +26,7 @@ private: SEARCHING_STATE, TRACKING_STATE, STANDBY_STATE } State; - EnemyColor enemy_color; + const EnemyColor &enemy_color; State state; cv::Rect2d armor_box; cv::Ptr tracker; @@ -35,7 +35,7 @@ private: Classifier classifier; int contour_area; - Uart &uart; + Serial &serial; const bool &use_classifier; bool stateSearchingTarget(cv::Mat &src); @@ -51,7 +51,7 @@ struct LightBlob { double length; explicit LightBlob(cv::RotatedRect &r) : rect(r) { - length = std::max(rect.size.height, rect.size.width); + length = max(rect.size.height, rect.size.width); }; bool operator<(LightBlob &l2) { return this->rect.center.x < l2.rect.center.x; } bool operator<=(LightBlob &l2) { return this->rect.center.x <= l2.rect.center.x; } diff --git a/armor/src/armor_finder/armor_finder.cpp b/armor/src/armor_finder/armor_finder.cpp index 2904e41..7c558c3 100644 --- a/armor/src/armor_finder/armor_finder.cpp +++ b/armor/src/armor_finder/armor_finder.cpp @@ -1,15 +1,15 @@ // // Created by xinyang on 19-3-27. // -//#define LOG_LEVEL LOG_NONE +#define LOG_LEVEL LOG_NONE #include #include #include #include #include -ArmorFinder::ArmorFinder(EnemyColor color, Uart &u, string paras_folder, const bool &use) : - uart(u), +ArmorFinder::ArmorFinder(EnemyColor &color, Serial &u, string paras_folder, const bool &use) : + serial(u), enemy_color(color), state(STANDBY_STATE), classifier(std::move(paras_folder)), @@ -62,16 +62,47 @@ void ArmorFinder::run(cv::Mat &src) { #define FOCUS_PIXAL (600) +bool sendTarget(Serial& serial, double x, double y, double z) { + static short x_tmp, y_tmp, z_tmp; + static time_t last_time = time(nullptr); + static int fps; + uint8_t buff[8]; + + static SYSTEMTIME ts, te; + GetLocalTime(&te); + printf("Interval: %d\n", (te.wSecond - ts.wSecond) * 1000 + (te.wMilliseconds - ts.wMilliseconds)); + ts = te; + + time_t t = time(nullptr); + if (last_time != t) { + last_time = t; + cout << "fps:" << fps << ", (" << x << "," << y << "," << z << ")" << endl; + fps = 0; + } + fps += 1; + + x_tmp = static_cast(x * (32768 - 1) / 100); + y_tmp = static_cast(y * (32768 - 1) / 100); + z_tmp = static_cast(z * (32768 - 1) / 1000); + + buff[0] = 's'; + buff[1] = static_cast((x_tmp >> 8) & 0xFF); + buff[2] = static_cast((x_tmp >> 0) & 0xFF); + buff[3] = static_cast((y_tmp >> 8) & 0xFF); + buff[4] = static_cast((y_tmp >> 0) & 0xFF); + buff[5] = static_cast((z_tmp >> 8) & 0xFF); + buff[6] = static_cast((z_tmp >> 0) & 0xFF); + buff[7] = 'e'; + + return serial.WriteData(buff, sizeof(buff)); +} + bool ArmorFinder::sendBoxPosition() { - static int dx_add = 0; auto rect = armor_box; - double dx = rect.x + rect.width/2 - 320 - 8; - dx_add += dx; - dx = dx + dx_add * 0; + double dx = rect.x + rect.width/2 - 320; double dy = rect.y + rect.height/2 - 240 - 30; double yaw = atan(dx / FOCUS_PIXAL) * 180 / 3.14159265459; double pitch = atan(dy / FOCUS_PIXAL) * 180 / 3.14159265459; // cout << yaw << endl; - uart.sendTarget(yaw, -pitch, 0); - return true; + return sendTarget(serial, yaw, -pitch, 0); } \ No newline at end of file diff --git a/energy/include/energy/energy.h b/energy/include/energy/energy.h index 71a5455..b62627e 100644 --- a/energy/include/energy/energy.h +++ b/energy/include/energy/energy.h @@ -14,19 +14,19 @@ #include #include "energy/constant.h" #include "energy/param_struct_define.h" -#include "uart/uart.h" +#include "serial/serial.h" using std::vector; class Energy { public: - Energy(Uart &u); + Energy(Serial &u, int &ally_color); ~Energy(); int run(cv::Mat &src); cv::Point2f uart_hit_point; clock_t start; - Uart &uart; + Serial &serial; void setAllyColor(int color); void setRotation(int rotation); @@ -51,7 +51,7 @@ private: double last_target_position; double last_hit_position; float target_armor; - int ally_color_; + int &ally_color_; int energy_part_rotation; float attack_distance; int send_cnt; diff --git a/energy/src/energy/energy.cpp b/energy/src/energy/energy.cpp index 0aad5d2..6020aa8 100644 --- a/energy/src/energy/energy.cpp +++ b/energy/src/energy/energy.cpp @@ -8,7 +8,7 @@ using std::cout; using std::endl; using std::vector; -Energy::Energy(Uart &u):uart(u), +Energy::Energy(Serial &u, int &ally_color):serial(u),ally_color_(ally_color), src_blue(SRC_HEIGHT, SRC_WIDTH, CV_8UC1), src_red(SRC_HEIGHT, SRC_WIDTH, CV_8UC1) { diff --git a/energy/src/energy/get/gimble_rotation_get.cpp b/energy/src/energy/get/gimble_rotation_get.cpp index b19f644..3d69210 100644 --- a/energy/src/energy/get/gimble_rotation_get.cpp +++ b/energy/src/energy/get/gimble_rotation_get.cpp @@ -13,48 +13,37 @@ extern float curr_yaw, curr_pitch, mark_yaw, mark_pitch; void Energy::gimbleRotation(){ -//该方法用于标定激光零点的情况,对操作手友好,但建立在云台稳定情况下 -// yaw_rotation = static_cast(180 / PI * atan2(-1*STRETCH*(hit_point.x-ZERO_POINT_X), ATTACK_DISTANCE)); -// pitch_rotation = static_cast(180 / PI * atan2((ATTACK_DISTANCE*tan(PITCH_ORIGIN_RAD)-STRETCH*(hit_point.y-ZERO_POINT_Y)), ATTACK_DISTANCE)); - -//该方法用于操作手自己完成对心工作的情况,对操作手要求高 - cv::Point2f real_hit_point; + cv::Point2f real_hit_point; stretch(hit_point, real_hit_point); -// yaw_rotation = static_cast(180 / PI * atan2((ATTACK_DISTANCE*tan(YAW_ORIGIN_RAD)-real_hit_point.x), ATTACK_DISTANCE)); -// pitch_rotation = static_cast(180 / PI * atan2((ATTACK_DISTANCE*tan(PITCH_ORIGIN_RAD)-real_hit_point.y), ATTACK_DISTANCE)); -// yaw_rotation = static_cast(180 / PI * atan2((attack_distance*tan(mark_yaw*PI/180)-real_hit_point.x), attack_distance)); -// pitch_rotation = static_cast(180 / PI * atan2((attack_distance*tan(mark_pitch*PI/180)-real_hit_point.y), attack_distance)); - mark_yaw = -1.41; - mark_pitch = 12.79; + if(position_mode == 1){ - yaw_rotation = static_cast(180 / PI * atan2((attack_distance*tan(mark_yaw*PI/180)-real_hit_point.x), attack_distance)); + yaw_rotation = static_cast(180 / PI * atan2((attack_distance * tan(mark_yaw * PI / 180) - real_hit_point.x), attack_distance)); pitch_rotation = static_cast(180 / PI * atan2((attack_distance*tan(mark_pitch*PI/180)-real_hit_point.y), attack_distance)); } else if(position_mode == 2){ - yaw_rotation = static_cast(180 / PI * atan2((attack_distance*tan(mark_yaw*PI/180)-real_hit_point.x), attack_distance)); + yaw_rotation = static_cast(180 / PI * atan2((attack_distance * tan(mark_yaw * PI / 180) - real_hit_point.x), attack_distance)); pitch_rotation = static_cast(180 / PI * atan2((attack_distance*tan(mark_pitch*PI/180)-real_hit_point.y), attack_distance)); } else if(position_mode == 3){ - yaw_rotation = -0.5+static_cast(180 / PI * atan2((attack_distance*tan(mark_yaw*PI/180)-real_hit_point.x), attack_distance)); - pitch_rotation = 1.5+static_cast(180 / PI * atan2((attack_distance*tan(mark_pitch*PI/180)-real_hit_point.y), attack_distance)); - } - else if(position_mode == 4){ - yaw_rotation = -2+static_cast(180 / PI * atan2((attack_distance*tan(mark_yaw*PI/180)-real_hit_point.x), attack_distance)); - pitch_rotation = 1+static_cast(180 / PI * atan2((attack_distance*tan(mark_pitch*PI/180)-real_hit_point.y), attack_distance)); - } - else if(position_mode == 5){ - yaw_rotation = -0.5+static_cast(180 / PI * atan2((attack_distance*tan(mark_yaw*PI/180)-real_hit_point.x), attack_distance)); - pitch_rotation = 0.5+static_cast(180 / PI * atan2((attack_distance*tan(mark_pitch*PI/180)-real_hit_point.y), attack_distance)); - } - else if(position_mode == 6){ - yaw_rotation = -1+static_cast(180 / PI * atan2((attack_distance*tan(mark_yaw*PI/180)-real_hit_point.x), attack_distance)); - pitch_rotation = 1+static_cast(180 / PI * atan2((attack_distance*tan(mark_pitch*PI/180)-real_hit_point.y), attack_distance)); - } - else{ - yaw_rotation = static_cast(180 / PI * atan2((attack_distance*tan(mark_yaw*PI/180)-real_hit_point.x), attack_distance)); + yaw_rotation = static_cast(180 / PI * atan2((attack_distance * tan(mark_yaw * PI / 180) - real_hit_point.x), attack_distance)); pitch_rotation = static_cast(180 / PI * atan2((attack_distance*tan(mark_pitch*PI/180)-real_hit_point.y), attack_distance)); } + else if(position_mode == 4){ + yaw_rotation = static_cast(180 / PI * atan2((attack_distance * tan(mark_yaw * PI / 180) - real_hit_point.x), attack_distance)); + pitch_rotation = static_cast(180 / PI * atan2((attack_distance*tan(mark_pitch*PI/180)-real_hit_point.y), attack_distance)); + } + else if(position_mode == 5){ + yaw_rotation = static_cast(180 / PI * atan2((attack_distance * tan(mark_yaw * PI / 180) - real_hit_point.x), attack_distance)); + pitch_rotation = static_cast(180 / PI * atan2((attack_distance*tan(mark_pitch*PI/180)-real_hit_point.y), attack_distance)); + } + else if(position_mode == 6){ + yaw_rotation = static_cast(180 / PI * atan2((attack_distance * tan(mark_yaw * PI / 180) - real_hit_point.x), attack_distance)); + pitch_rotation = static_cast(180 / PI * atan2((attack_distance*tan(mark_pitch*PI/180)-real_hit_point.y), attack_distance)); + } +// else{ +// pitch_rotation = 5.5+static_cast(180 / PI * atan2((attack_distance*tan(mark_pitch*PI/180)-real_hit_point.y), attack_distance)); +// } // yaw_rotation = static_cast(180 / PI * atan2((ATTACK_DISTANCE*tan(3.5*PI/180)-STRETCH*(hit_point.x-cycle_center.x)), ATTACK_DISTANCE)); diff --git a/energy/src/energy/get/hit_point_get.cpp b/energy/src/energy/get/hit_point_get.cpp index a8c495b..364d2dc 100644 --- a/energy/src/energy/get/hit_point_get.cpp +++ b/energy/src/energy/get/hit_point_get.cpp @@ -15,53 +15,50 @@ void Energy::getHitPoint(){ int limit_angle = 6; int angle_interval = 60; - if(energy_part_rotation==1){ //顺时针 + if(energy_part_rotation==1){ if(target_armor>=0 && target_armor<=limit_angle){ hit_point.x = cycle_center.x + static_cast(radius / 2); hit_point.y = cycle_center.y + static_cast(radius * sqrt(3) / 2); - hit_position = -1*angle_interval;//-60 + hit_position = -1*angle_interval; position_mode = 1; -// cout<<"666"<<'\t'<=angle_interval && target_armor(radius); hit_point.y = cycle_center.y; - hit_position = 0;//0 + hit_position = 0; position_mode = 2; } else if(target_armor>=angle_interval*2 && target_armor<=angle_interval*2+limit_angle){ hit_point.x = cycle_center.x + static_cast(radius / 2); hit_point.y = cycle_center.y - static_cast(radius * sqrt(3) / 2); - hit_position = angle_interval;//60 + hit_position = angle_interval; position_mode = 3; } else if(target_armor>=-180 && target_armor<-180+limit_angle){ hit_point.x = cycle_center.x - static_cast(radius / 2); hit_point.y = cycle_center.y - static_cast(radius * sqrt(3) / 2); - hit_position = 2*angle_interval;//120 + hit_position = 2*angle_interval; position_mode = 4; } else if(target_armor>=-2*angle_interval&&target_armor<-2*angle_interval+limit_angle){ hit_point.x = cycle_center.x - static_cast(radius); hit_point.y = cycle_center.y; - hit_position = 180;//180 + hit_position = 180; position_mode = 5; } else if(target_armor>=-1*angle_interval&&target_armor<-1*angle_interval+limit_angle) { hit_point.x = cycle_center.x - static_cast(radius / 2); hit_point.y = cycle_center.y + static_cast(radius * sqrt(3) / 2); - hit_position = -2 * angle_interval;//-120 + hit_position = -2 * angle_interval; position_mode = 6; } else{ -// last_hit_position = 2000; position_mode = 0; return; } } - if(energy_part_rotation==-1){ //逆时针 + if(energy_part_rotation==-1){ if(target_armor>=0 && target_armor<=limit_angle){ hit_point.x = cycle_center.x - static_cast(radius / 2); hit_point.y = cycle_center.y - static_cast(radius * sqrt(3) / 2); @@ -99,55 +96,26 @@ void Energy::getHitPoint(){ position_mode = 6; } else{ -// last_hit_position = 2000; position_mode = 0; return; } } - -// cout<<"last: "<360&&last_hit_position>360){ -// isSendTarget = false; -// return; -// } - -// if(fabs(hit_position - last_hit_position) < 15||fabs(hit_position - last_hit_position) > 345 && fabs(hit_position - last_hit_position) <= 360){ -// last_hit_position = hit_position; -// isSendTarget = false; -// return; -// } -// else{ -// last_hit_position = hit_position; -// isSendTarget = true; -// cout<<"hit position: "<(energy_part_rotation * energy_part_param_.RPM -// * energy_part_param_.HIT_TIME * 360 / 60); -// rotate(rad, radius, cycle_center, target_center, hit_point); } bool Energy::changeTarget(){ diff --git a/energy/src/energy/send_target_by_uart/send_target_by_uart.cpp b/energy/src/energy/send_target_by_uart/send_target_by_uart.cpp index d9cc9ce..e7a516f 100644 --- a/energy/src/energy/send_target_by_uart/send_target_by_uart.cpp +++ b/energy/src/energy/send_target_by_uart/send_target_by_uart.cpp @@ -3,11 +3,41 @@ // #include "energy/energy.h" +bool sendTarget(Serial& serial, float x, float y, float z) { + static short x_tmp, y_tmp, z_tmp; + static time_t last_time = time(nullptr); + static int fps; + uint8_t buff[8]; + + time_t t = time(nullptr); + if (last_time != t) { + last_time = t; + std::cout << "fps:" << fps << ", (" << x << "," << y << "," << z << ")" << std::endl; + fps = 0; + } + fps += 1; + + x_tmp = static_cast(x * (32768 - 1) / 100); + y_tmp = static_cast(y * (32768 - 1) / 100); + z_tmp = static_cast(z * (32768 - 1) / 1000); + + buff[0] = 's'; + buff[1] = static_cast((x_tmp >> 8) & 0xFF); + buff[2] = static_cast((x_tmp >> 0) & 0xFF); + buff[3] = static_cast((y_tmp >> 8) & 0xFF); + buff[4] = static_cast((y_tmp >> 0) & 0xFF); + buff[5] = static_cast((z_tmp >> 8) & 0xFF); + buff[6] = static_cast((z_tmp >> 0) & 0xFF); + buff[7] = 'e'; + + return serial.WriteData(buff, sizeof(buff)); +} + void Energy::sendTargetByUart(float x, float y, float z) { // if(!changeTarget()){ // return; // } - uart.sendTarget(x, y, z); + sendTarget(serial, x, y, z); send_cnt+=1; } diff --git a/main.cpp b/main.cpp index 0941554..97b9fb5 100644 --- a/main.cpp +++ b/main.cpp @@ -5,7 +5,7 @@ #include #include -#include +#include #include #include #include @@ -18,7 +18,6 @@ #define DO_NOT_CNT_TIME #include -#define PROJECT_DIR PATH #define ENERGY_STATE 1 #define ARMOR_STATE 0 @@ -30,18 +29,20 @@ int state = ENERGY_STATE; float curr_yaw = 0, curr_pitch = 0; float mark_yaw = 0, mark_pitch = 0; int mark = 0; +EnemyColor enemy_color = ENEMY_BLUE; +int ally_color = ALLY_RED; bool use_classifier = true; -void uartReceive(Uart *uart); +void uartReceive(Serial *uart); int main(int argc, char *argv[]) { process_options(argc, argv); - Uart uart; -// thread receive(uartReceive, &uart); + Serial uart(3, 115200); + thread receive(uartReceive, &uart); bool flag = true; while (flag) { - int ally_color = ALLY_RED; + int energy_part_rotation = CLOCKWISE; int from_camera = 1; @@ -53,13 +54,13 @@ int main(int argc, char *argv[]) { WrapperHead *video_armor; WrapperHead *video_energy; if (from_camera) { - video_armor = new CameraWrapper(0/*, "armor"*/); -// video_energy = new CameraWrapper(1, "energy"); + video_armor = new CameraWrapper(0, "armor"); + video_energy = new CameraWrapper(1, "energy"); } else { video_armor = new VideoWrapper("/home/xinyang/Desktop/DataSets/video/blue_4.mp4"); video_energy = new VideoWrapper("/home/xinyang/Desktop/DataSets/video/blue_4.mp4"); } - if (video_armor->init()/* && video_energy->init()*/) { + if (video_armor->init() && video_energy->init()) { cout << "Video source initialization successfully." << endl; } else { delete video_armor; @@ -71,19 +72,19 @@ int main(int argc, char *argv[]) { Mat energy_src, armor_src; for(int i=0; i<10; i++){ video_armor->read(armor_src); -// video_energy->read(armor_src); + video_energy->read(armor_src); } - ArmorFinder armorFinder(ENEMY_BLUE, uart, PROJECT_DIR"/tools/para/", use_classifier); + ArmorFinder armorFinder(enemy_color, uart, PROJECT_DIR"/tools/para/", use_classifier); - Energy energy(uart); - energy.setAllyColor(ally_color); + Energy energy(uart, ally_color); +// energy.setAllyColor(ally_color); energy.setRotation(energy_part_rotation); - bool ok = video_armor->read(armor_src)/* && video_energy->read(armor_src)*/; + bool ok = video_armor->read(armor_src) && video_energy->read(armor_src); while (ok) { - CNT_TIME(WORD_LIGHT_CYAN, "Total", { + CNT_TIME("Total", { if (state == ENERGY_STATE) { ok = video_energy->read(energy_src); if (show_origin) { @@ -95,10 +96,11 @@ int main(int argc, char *argv[]) { energy.run(energy_src); } else { ok = video_armor->read(armor_src); + flip(armor_src, armor_src, 0); if (show_origin) { imshow("armor src", armor_src); } - CNT_TIME(WORD_LIGHT_BLUE, "Armor Time", { + CNT_TIME("Armor Time", { armorFinder.run(armor_src); }); } @@ -116,47 +118,65 @@ int main(int argc, char *argv[]) { return 0; } -#define RECEIVE_LOG_LEVEL LOG_MSG +#define RECEIVE_LOG_LEVEL LOG_NOTHING -void uartReceive(Uart *uart) { +char uartReadByte(Serial &uart) { + while (uart.GetBytesInCOM() == 0); + char byte; + if (uart.ReadData((uint8_t*)& byte, 1) == false) { + LOGE("serial error!"); + } + return byte; +} + +void uartReceive(Serial* uart) { char buffer[100]; int cnt = 0; LOGM("data receive start!"); while (true) { char data; - while ((data = uart->receive()) != '\n') { + while ((data = uartReadByte(*uart)) != '\n') { buffer[cnt++] = data; if (cnt >= 100) { -// LOG(RECEIVE_LOG_LEVEL, "data receive over flow!"); + LOG(RECEIVE_LOG_LEVEL, "data receive over flow!"); cnt = 0; } } -// LOGM("%d", cnt); - if (cnt == 11) { + LOGM("%d", cnt); + if (cnt == 12) { if (buffer[8] == 'e') { state = ENERGY_STATE; -// LOG(RECEIVE_LOG_LEVEL, "Energy state"); + LOG(RECEIVE_LOG_LEVEL, "Energy state"); } else if (buffer[8] == 'a') { state = ARMOR_STATE; -// LOG(RECEIVE_LOG_LEVEL, "Armor state"); + LOG(RECEIVE_LOG_LEVEL, "Armor state"); } if (buffer[10] == 0){ use_classifier = false; -// LOG(RECEIVE_LOG_LEVEL, "Classifier off!"); + LOG(RECEIVE_LOG_LEVEL, "Classifier off!"); } else if(buffer[10] == 1){ use_classifier = true; -// LOG(RECEIVE_LOG_LEVEL, "Classifier on!"); + LOG(RECEIVE_LOG_LEVEL, "Classifier on!"); } + if (buffer[11] == ENEMY_BLUE) { + LOG(RECEIVE_LOG_LEVEL, "ENEMY_BLUE!"); + ally_color = ALLY_RED; + enemy_color = ENEMY_BLUE; + } else if (buffer[11] == ENEMY_RED) { + LOG(RECEIVE_LOG_LEVEL, "ENEMY_RED!"); + ally_color = ALLY_BLUE; + enemy_color = ENEMY_RED; + } memcpy(&curr_yaw, buffer, 4); memcpy(&curr_pitch, buffer + 4, 4); -// LOG(RECEIVE_LOG_LEVEL, "Get yaw:%f pitch:%f", curr_yaw, curr_pitch); + LOG(RECEIVE_LOG_LEVEL, "Get yaw:%f pitch:%f", curr_yaw, curr_pitch); if (buffer[9] == 1) { if (mark == 0) { mark = 1; mark_yaw = curr_yaw; mark_pitch = curr_pitch; } -// LOG(RECEIVE_LOG_LEVEL, "Marked"); + LOG(RECEIVE_LOG_LEVEL, "Marked"); } } cnt = 0; diff --git a/others/armor.Config b/others/armor.Config new file mode 100644 index 0000000..d5f03ee --- /dev/null +++ b/others/armor.Config @@ -0,0 +1,153 @@ +create_time = "2019-05-13 20:58:58"; +internal_id = "E7FCFFE8999B"; +resolution : +{ + image_size : + { + iIndex = 1; + acDescription = "640X480 ROI"; + uBinSumMode = 0; + uBinAverageMode = 0; + uSkipMode = 0; + uResampleMask = 0; + iHOffsetFOV = 56; + iVOffsetFOV = 0; + iWidthFOV = 640; + iHeightFOV = 480; + iWidth = 640; + iHeight = 480; + iWidthZoomHd = 0; + iHeightZoomHd = 0; + iWidthZoomSw = 0; + iHeightZoomSw = 0; + }; + image_size_for_snap : + { + iIndex = 255; + acDescription = ""; + uBinSumMode = 0; + uBinAverageMode = 0; + uSkipMode = 0; + uResampleMask = 0; + iHOffsetFOV = 0; + iVOffsetFOV = 0; + iWidthFOV = 0; + iHeightFOV = 0; + iWidth = 0; + iHeight = 0; + iWidthZoomHd = 0; + iHeightZoomHd = 0; + iWidthZoomSw = 0; + iHeightZoomSw = 0; + }; + transfer_roi_mask = 0; + transfer_roi_x1 = [ 0, 0, 0, 0 ]; + transfer_roi_y1 = [ 0, 0, 0, 0 ]; + transfer_roi_x2 = [ 0, 0, 0, 0 ]; + transfer_roi_y2 = [ 0, 0, 0, 0 ]; +}; +exposure : +{ + anti_flick_freq = 0; + anti_flick = false; + show_ae_window = false; + ae_window_height = 0; + ae_window_width = 0; + ae_window_voff = 0; + ae_window_hoff = 0; + analog_gain = 64; + exp_time = 10000.0; + ae_target = 120; + ae_enable = false; + user_exposure_time = 10000.0; + user_ae_min_exposure_time = 0.0; + user_ae_max_exposure_time = 10000000.0; + user_ae_min_analog_gain = 16; + user_ae_max_analog_gain = 64; + ae_threshold = 10; +}; +video_format : +{ + frame_speed_sel = 1; + trans_pack_len_sel = 0; + media_type_sel = 0; + auto_reconnect = true; + hdr_gain_mode = 0; +}; +overlay : +{ + cross_line : + { + show = [ false, false, false, false, false, false, false, false, false ]; + color = [ 6458569, 15539236, 16756425, 13156327, 16773632, 0, 0, 0, 0 ]; + pos = [ 376, 240, 188, 120, 564, 120, 188, 360, 564, 360, 0, 0, 0, 0, 0, 0, 0, 0 ]; + }; +}; +isp_color : +{ + auto_wb = false; + mono = false; + inverse = false; + r_gain = 195; + g_gain = 174; + b_gain = 180; + wb_window_hoff = 0; + wb_window_voff = 0; + wb_window_width = 0; + wb_window_height = 0; + show_wb_window = false; + saturation = 100; + clr_temp_mode = 0; + clr_temp_sel = 1; + user_clr_temp : + { + desc = ""; + matrix = [ 1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0 ]; + r = 1.0; + g = 1.0; + b = 1.0; + }; + raw2rgb_algorithm_sw_sel = 1; +}; +isp_lut : +{ + lut_preset_sel = 0; + lut_mode = 1; + user_def_lut = [ 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 256, 257, 258, 259, 260, 261, 262, 263, 264, 265, 266, 267, 268, 269, 270, 271, 272, 273, 274, 275, 276, 277, 278, 279, 280, 281, 282, 283, 284, 285, 286, 287, 288, 289, 290, 291, 292, 293, 294, 295, 296, 297, 298, 299, 300, 301, 302, 303, 304, 305, 306, 307, 308, 309, 310, 311, 312, 313, 314, 315, 316, 317, 318, 319, 320, 321, 322, 323, 324, 325, 326, 327, 328, 329, 330, 331, 332, 333, 334, 335, 336, 337, 338, 339, 340, 341, 342, 343, 344, 345, 346, 347, 348, 349, 350, 351, 352, 353, 354, 355, 356, 357, 358, 359, 360, 361, 362, 363, 364, 365, 366, 367, 368, 369, 370, 371, 372, 373, 374, 375, 376, 377, 378, 379, 380, 381, 382, 383, 384, 385, 386, 387, 388, 389, 390, 391, 392, 393, 394, 395, 396, 397, 398, 399, 400, 401, 402, 403, 404, 405, 406, 407, 408, 409, 410, 411, 412, 413, 414, 415, 416, 417, 418, 419, 420, 421, 422, 423, 424, 425, 426, 427, 428, 429, 430, 431, 432, 433, 434, 435, 436, 437, 438, 439, 440, 441, 442, 443, 444, 445, 446, 447, 448, 449, 450, 451, 452, 453, 454, 455, 456, 457, 458, 459, 460, 461, 462, 463, 464, 465, 466, 467, 468, 469, 470, 471, 472, 473, 474, 475, 476, 477, 478, 479, 480, 481, 482, 483, 484, 485, 486, 487, 488, 489, 490, 491, 492, 493, 494, 495, 496, 497, 498, 499, 500, 501, 502, 503, 504, 505, 506, 507, 508, 509, 510, 511, 512, 513, 514, 515, 516, 517, 518, 519, 520, 521, 522, 523, 524, 525, 526, 527, 528, 529, 530, 531, 532, 533, 534, 535, 536, 537, 538, 539, 540, 541, 542, 543, 544, 545, 546, 547, 548, 549, 550, 551, 552, 553, 554, 555, 556, 557, 558, 559, 560, 561, 562, 563, 564, 565, 566, 567, 568, 569, 570, 571, 572, 573, 574, 575, 576, 577, 578, 579, 580, 581, 582, 583, 584, 585, 586, 587, 588, 589, 590, 591, 592, 593, 594, 595, 596, 597, 598, 599, 600, 601, 602, 603, 604, 605, 606, 607, 608, 609, 610, 611, 612, 613, 614, 615, 616, 617, 618, 619, 620, 621, 622, 623, 624, 625, 626, 627, 628, 629, 630, 631, 632, 633, 634, 635, 636, 637, 638, 639, 640, 641, 642, 643, 644, 645, 646, 647, 648, 649, 650, 651, 652, 653, 654, 655, 656, 657, 658, 659, 660, 661, 662, 663, 664, 665, 666, 667, 668, 669, 670, 671, 672, 673, 674, 675, 676, 677, 678, 679, 680, 681, 682, 683, 684, 685, 686, 687, 688, 689, 690, 691, 692, 693, 694, 695, 696, 697, 698, 699, 700, 701, 702, 703, 704, 705, 706, 707, 708, 709, 710, 711, 712, 713, 714, 715, 716, 717, 718, 719, 720, 721, 722, 723, 724, 725, 726, 727, 728, 729, 730, 731, 732, 733, 734, 735, 736, 737, 738, 739, 740, 741, 742, 743, 744, 745, 746, 747, 748, 749, 750, 751, 752, 753, 754, 755, 756, 757, 758, 759, 760, 761, 762, 763, 764, 765, 766, 767, 768, 769, 770, 771, 772, 773, 774, 775, 776, 777, 778, 779, 780, 781, 782, 783, 784, 785, 786, 787, 788, 789, 790, 791, 792, 793, 794, 795, 796, 797, 798, 799, 800, 801, 802, 803, 804, 805, 806, 807, 808, 809, 810, 811, 812, 813, 814, 815, 816, 817, 818, 819, 820, 821, 822, 823, 824, 825, 826, 827, 828, 829, 830, 831, 832, 833, 834, 835, 836, 837, 838, 839, 840, 841, 842, 843, 844, 845, 846, 847, 848, 849, 850, 851, 852, 853, 854, 855, 856, 857, 858, 859, 860, 861, 862, 863, 864, 865, 866, 867, 868, 869, 870, 871, 872, 873, 874, 875, 876, 877, 878, 879, 880, 881, 882, 883, 884, 885, 886, 887, 888, 889, 890, 891, 892, 893, 894, 895, 896, 897, 898, 899, 900, 901, 902, 903, 904, 905, 906, 907, 908, 909, 910, 911, 912, 913, 914, 915, 916, 917, 918, 919, 920, 921, 922, 923, 924, 925, 926, 927, 928, 929, 930, 931, 932, 933, 934, 935, 936, 937, 938, 939, 940, 941, 942, 943, 944, 945, 946, 947, 948, 949, 950, 951, 952, 953, 954, 955, 956, 957, 958, 959, 960, 961, 962, 963, 964, 965, 966, 967, 968, 969, 970, 971, 972, 973, 974, 975, 976, 977, 978, 979, 980, 981, 982, 983, 984, 985, 986, 987, 988, 989, 990, 991, 992, 993, 994, 995, 996, 997, 998, 999, 1000, 1001, 1002, 1003, 1004, 1005, 1006, 1007, 1008, 1009, 1010, 1011, 1012, 1013, 1014, 1015, 1016, 1017, 1018, 1019, 1020, 1021, 1022, 1023, 1024, 1025, 1026, 1027, 1028, 1029, 1030, 1031, 1032, 1033, 1034, 1035, 1036, 1037, 1038, 1039, 1040, 1041, 1042, 1043, 1044, 1045, 1046, 1047, 1048, 1049, 1050, 1051, 1052, 1053, 1054, 1055, 1056, 1057, 1058, 1059, 1060, 1061, 1062, 1063, 1064, 1065, 1066, 1067, 1068, 1069, 1070, 1071, 1072, 1073, 1074, 1075, 1076, 1077, 1078, 1079, 1080, 1081, 1082, 1083, 1084, 1085, 1086, 1087, 1088, 1089, 1090, 1091, 1092, 1093, 1094, 1095, 1096, 1097, 1098, 1099, 1100, 1101, 1102, 1103, 1104, 1105, 1106, 1107, 1108, 1109, 1110, 1111, 1112, 1113, 1114, 1115, 1116, 1117, 1118, 1119, 1120, 1121, 1122, 1123, 1124, 1125, 1126, 1127, 1128, 1129, 1130, 1131, 1132, 1133, 1134, 1135, 1136, 1137, 1138, 1139, 1140, 1141, 1142, 1143, 1144, 1145, 1146, 1147, 1148, 1149, 1150, 1151, 1152, 1153, 1154, 1155, 1156, 1157, 1158, 1159, 1160, 1161, 1162, 1163, 1164, 1165, 1166, 1167, 1168, 1169, 1170, 1171, 1172, 1173, 1174, 1175, 1176, 1177, 1178, 1179, 1180, 1181, 1182, 1183, 1184, 1185, 1186, 1187, 1188, 1189, 1190, 1191, 1192, 1193, 1194, 1195, 1196, 1197, 1198, 1199, 1200, 1201, 1202, 1203, 1204, 1205, 1206, 1207, 1208, 1209, 1210, 1211, 1212, 1213, 1214, 1215, 1216, 1217, 1218, 1219, 1220, 1221, 1222, 1223, 1224, 1225, 1226, 1227, 1228, 1229, 1230, 1231, 1232, 1233, 1234, 1235, 1236, 1237, 1238, 1239, 1240, 1241, 1242, 1243, 1244, 1245, 1246, 1247, 1248, 1249, 1250, 1251, 1252, 1253, 1254, 1255, 1256, 1257, 1258, 1259, 1260, 1261, 1262, 1263, 1264, 1265, 1266, 1267, 1268, 1269, 1270, 1271, 1272, 1273, 1274, 1275, 1276, 1277, 1278, 1279, 1280, 1281, 1282, 1283, 1284, 1285, 1286, 1287, 1288, 1289, 1290, 1291, 1292, 1293, 1294, 1295, 1296, 1297, 1298, 1299, 1300, 1301, 1302, 1303, 1304, 1305, 1306, 1307, 1308, 1309, 1310, 1311, 1312, 1313, 1314, 1315, 1316, 1317, 1318, 1319, 1320, 1321, 1322, 1323, 1324, 1325, 1326, 1327, 1328, 1329, 1330, 1331, 1332, 1333, 1334, 1335, 1336, 1337, 1338, 1339, 1340, 1341, 1342, 1343, 1344, 1345, 1346, 1347, 1348, 1349, 1350, 1351, 1352, 1353, 1354, 1355, 1356, 1357, 1358, 1359, 1360, 1361, 1362, 1363, 1364, 1365, 1366, 1367, 1368, 1369, 1370, 1371, 1372, 1373, 1374, 1375, 1376, 1377, 1378, 1379, 1380, 1381, 1382, 1383, 1384, 1385, 1386, 1387, 1388, 1389, 1390, 1391, 1392, 1393, 1394, 1395, 1396, 1397, 1398, 1399, 1400, 1401, 1402, 1403, 1404, 1405, 1406, 1407, 1408, 1409, 1410, 1411, 1412, 1413, 1414, 1415, 1416, 1417, 1418, 1419, 1420, 1421, 1422, 1423, 1424, 1425, 1426, 1427, 1428, 1429, 1430, 1431, 1432, 1433, 1434, 1435, 1436, 1437, 1438, 1439, 1440, 1441, 1442, 1443, 1444, 1445, 1446, 1447, 1448, 1449, 1450, 1451, 1452, 1453, 1454, 1455, 1456, 1457, 1458, 1459, 1460, 1461, 1462, 1463, 1464, 1465, 1466, 1467, 1468, 1469, 1470, 1471, 1472, 1473, 1474, 1475, 1476, 1477, 1478, 1479, 1480, 1481, 1482, 1483, 1484, 1485, 1486, 1487, 1488, 1489, 1490, 1491, 1492, 1493, 1494, 1495, 1496, 1497, 1498, 1499, 1500, 1501, 1502, 1503, 1504, 1505, 1506, 1507, 1508, 1509, 1510, 1511, 1512, 1513, 1514, 1515, 1516, 1517, 1518, 1519, 1520, 1521, 1522, 1523, 1524, 1525, 1526, 1527, 1528, 1529, 1530, 1531, 1532, 1533, 1534, 1535, 1536, 1537, 1538, 1539, 1540, 1541, 1542, 1543, 1544, 1545, 1546, 1547, 1548, 1549, 1550, 1551, 1552, 1553, 1554, 1555, 1556, 1557, 1558, 1559, 1560, 1561, 1562, 1563, 1564, 1565, 1566, 1567, 1568, 1569, 1570, 1571, 1572, 1573, 1574, 1575, 1576, 1577, 1578, 1579, 1580, 1581, 1582, 1583, 1584, 1585, 1586, 1587, 1588, 1589, 1590, 1591, 1592, 1593, 1594, 1595, 1596, 1597, 1598, 1599, 1600, 1601, 1602, 1603, 1604, 1605, 1606, 1607, 1608, 1609, 1610, 1611, 1612, 1613, 1614, 1615, 1616, 1617, 1618, 1619, 1620, 1621, 1622, 1623, 1624, 1625, 1626, 1627, 1628, 1629, 1630, 1631, 1632, 1633, 1634, 1635, 1636, 1637, 1638, 1639, 1640, 1641, 1642, 1643, 1644, 1645, 1646, 1647, 1648, 1649, 1650, 1651, 1652, 1653, 1654, 1655, 1656, 1657, 1658, 1659, 1660, 1661, 1662, 1663, 1664, 1665, 1666, 1667, 1668, 1669, 1670, 1671, 1672, 1673, 1674, 1675, 1676, 1677, 1678, 1679, 1680, 1681, 1682, 1683, 1684, 1685, 1686, 1687, 1688, 1689, 1690, 1691, 1692, 1693, 1694, 1695, 1696, 1697, 1698, 1699, 1700, 1701, 1702, 1703, 1704, 1705, 1706, 1707, 1708, 1709, 1710, 1711, 1712, 1713, 1714, 1715, 1716, 1717, 1718, 1719, 1720, 1721, 1722, 1723, 1724, 1725, 1726, 1727, 1728, 1729, 1730, 1731, 1732, 1733, 1734, 1735, 1736, 1737, 1738, 1739, 1740, 1741, 1742, 1743, 1744, 1745, 1746, 1747, 1748, 1749, 1750, 1751, 1752, 1753, 1754, 1755, 1756, 1757, 1758, 1759, 1760, 1761, 1762, 1763, 1764, 1765, 1766, 1767, 1768, 1769, 1770, 1771, 1772, 1773, 1774, 1775, 1776, 1777, 1778, 1779, 1780, 1781, 1782, 1783, 1784, 1785, 1786, 1787, 1788, 1789, 1790, 1791, 1792, 1793, 1794, 1795, 1796, 1797, 1798, 1799, 1800, 1801, 1802, 1803, 1804, 1805, 1806, 1807, 1808, 1809, 1810, 1811, 1812, 1813, 1814, 1815, 1816, 1817, 1818, 1819, 1820, 1821, 1822, 1823, 1824, 1825, 1826, 1827, 1828, 1829, 1830, 1831, 1832, 1833, 1834, 1835, 1836, 1837, 1838, 1839, 1840, 1841, 1842, 1843, 1844, 1845, 1846, 1847, 1848, 1849, 1850, 1851, 1852, 1853, 1854, 1855, 1856, 1857, 1858, 1859, 1860, 1861, 1862, 1863, 1864, 1865, 1866, 1867, 1868, 1869, 1870, 1871, 1872, 1873, 1874, 1875, 1876, 1877, 1878, 1879, 1880, 1881, 1882, 1883, 1884, 1885, 1886, 1887, 1888, 1889, 1890, 1891, 1892, 1893, 1894, 1895, 1896, 1897, 1898, 1899, 1900, 1901, 1902, 1903, 1904, 1905, 1906, 1907, 1908, 1909, 1910, 1911, 1912, 1913, 1914, 1915, 1916, 1917, 1918, 1919, 1920, 1921, 1922, 1923, 1924, 1925, 1926, 1927, 1928, 1929, 1930, 1931, 1932, 1933, 1934, 1935, 1936, 1937, 1938, 1939, 1940, 1941, 1942, 1943, 1944, 1945, 1946, 1947, 1948, 1949, 1950, 1951, 1952, 1953, 1954, 1955, 1956, 1957, 1958, 1959, 1960, 1961, 1962, 1963, 1964, 1965, 1966, 1967, 1968, 1969, 1970, 1971, 1972, 1973, 1974, 1975, 1976, 1977, 1978, 1979, 1980, 1981, 1982, 1983, 1984, 1985, 1986, 1987, 1988, 1989, 1990, 1991, 1992, 1993, 1994, 1995, 1996, 1997, 1998, 1999, 2000, 2001, 2002, 2003, 2004, 2005, 2006, 2007, 2008, 2009, 2010, 2011, 2012, 2013, 2014, 2015, 2016, 2017, 2018, 2019, 2020, 2021, 2022, 2023, 2024, 2025, 2026, 2027, 2028, 2029, 2030, 2031, 2032, 2033, 2034, 2035, 2036, 2037, 2038, 2039, 2040, 2041, 2042, 2043, 2044, 2045, 2046, 2047, 2048, 2049, 2050, 2051, 2052, 2053, 2054, 2055, 2056, 2057, 2058, 2059, 2060, 2061, 2062, 2063, 2064, 2065, 2066, 2067, 2068, 2069, 2070, 2071, 2072, 2073, 2074, 2075, 2076, 2077, 2078, 2079, 2080, 2081, 2082, 2083, 2084, 2085, 2086, 2087, 2088, 2089, 2090, 2091, 2092, 2093, 2094, 2095, 2096, 2097, 2098, 2099, 2100, 2101, 2102, 2103, 2104, 2105, 2106, 2107, 2108, 2109, 2110, 2111, 2112, 2113, 2114, 2115, 2116, 2117, 2118, 2119, 2120, 2121, 2122, 2123, 2124, 2125, 2126, 2127, 2128, 2129, 2130, 2131, 2132, 2133, 2134, 2135, 2136, 2137, 2138, 2139, 2140, 2141, 2142, 2143, 2144, 2145, 2146, 2147, 2148, 2149, 2150, 2151, 2152, 2153, 2154, 2155, 2156, 2157, 2158, 2159, 2160, 2161, 2162, 2163, 2164, 2165, 2166, 2167, 2168, 2169, 2170, 2171, 2172, 2173, 2174, 2175, 2176, 2177, 2178, 2179, 2180, 2181, 2182, 2183, 2184, 2185, 2186, 2187, 2188, 2189, 2190, 2191, 2192, 2193, 2194, 2195, 2196, 2197, 2198, 2199, 2200, 2201, 2202, 2203, 2204, 2205, 2206, 2207, 2208, 2209, 2210, 2211, 2212, 2213, 2214, 2215, 2216, 2217, 2218, 2219, 2220, 2221, 2222, 2223, 2224, 2225, 2226, 2227, 2228, 2229, 2230, 2231, 2232, 2233, 2234, 2235, 2236, 2237, 2238, 2239, 2240, 2241, 2242, 2243, 2244, 2245, 2246, 2247, 2248, 2249, 2250, 2251, 2252, 2253, 2254, 2255, 2256, 2257, 2258, 2259, 2260, 2261, 2262, 2263, 2264, 2265, 2266, 2267, 2268, 2269, 2270, 2271, 2272, 2273, 2274, 2275, 2276, 2277, 2278, 2279, 2280, 2281, 2282, 2283, 2284, 2285, 2286, 2287, 2288, 2289, 2290, 2291, 2292, 2293, 2294, 2295, 2296, 2297, 2298, 2299, 2300, 2301, 2302, 2303, 2304, 2305, 2306, 2307, 2308, 2309, 2310, 2311, 2312, 2313, 2314, 2315, 2316, 2317, 2318, 2319, 2320, 2321, 2322, 2323, 2324, 2325, 2326, 2327, 2328, 2329, 2330, 2331, 2332, 2333, 2334, 2335, 2336, 2337, 2338, 2339, 2340, 2341, 2342, 2343, 2344, 2345, 2346, 2347, 2348, 2349, 2350, 2351, 2352, 2353, 2354, 2355, 2356, 2357, 2358, 2359, 2360, 2361, 2362, 2363, 2364, 2365, 2366, 2367, 2368, 2369, 2370, 2371, 2372, 2373, 2374, 2375, 2376, 2377, 2378, 2379, 2380, 2381, 2382, 2383, 2384, 2385, 2386, 2387, 2388, 2389, 2390, 2391, 2392, 2393, 2394, 2395, 2396, 2397, 2398, 2399, 2400, 2401, 2402, 2403, 2404, 2405, 2406, 2407, 2408, 2409, 2410, 2411, 2412, 2413, 2414, 2415, 2416, 2417, 2418, 2419, 2420, 2421, 2422, 2423, 2424, 2425, 2426, 2427, 2428, 2429, 2430, 2431, 2432, 2433, 2434, 2435, 2436, 2437, 2438, 2439, 2440, 2441, 2442, 2443, 2444, 2445, 2446, 2447, 2448, 2449, 2450, 2451, 2452, 2453, 2454, 2455, 2456, 2457, 2458, 2459, 2460, 2461, 2462, 2463, 2464, 2465, 2466, 2467, 2468, 2469, 2470, 2471, 2472, 2473, 2474, 2475, 2476, 2477, 2478, 2479, 2480, 2481, 2482, 2483, 2484, 2485, 2486, 2487, 2488, 2489, 2490, 2491, 2492, 2493, 2494, 2495, 2496, 2497, 2498, 2499, 2500, 2501, 2502, 2503, 2504, 2505, 2506, 2507, 2508, 2509, 2510, 2511, 2512, 2513, 2514, 2515, 2516, 2517, 2518, 2519, 2520, 2521, 2522, 2523, 2524, 2525, 2526, 2527, 2528, 2529, 2530, 2531, 2532, 2533, 2534, 2535, 2536, 2537, 2538, 2539, 2540, 2541, 2542, 2543, 2544, 2545, 2546, 2547, 2548, 2549, 2550, 2551, 2552, 2553, 2554, 2555, 2556, 2557, 2558, 2559, 2560, 2561, 2562, 2563, 2564, 2565, 2566, 2567, 2568, 2569, 2570, 2571, 2572, 2573, 2574, 2575, 2576, 2577, 2578, 2579, 2580, 2581, 2582, 2583, 2584, 2585, 2586, 2587, 2588, 2589, 2590, 2591, 2592, 2593, 2594, 2595, 2596, 2597, 2598, 2599, 2600, 2601, 2602, 2603, 2604, 2605, 2606, 2607, 2608, 2609, 2610, 2611, 2612, 2613, 2614, 2615, 2616, 2617, 2618, 2619, 2620, 2621, 2622, 2623, 2624, 2625, 2626, 2627, 2628, 2629, 2630, 2631, 2632, 2633, 2634, 2635, 2636, 2637, 2638, 2639, 2640, 2641, 2642, 2643, 2644, 2645, 2646, 2647, 2648, 2649, 2650, 2651, 2652, 2653, 2654, 2655, 2656, 2657, 2658, 2659, 2660, 2661, 2662, 2663, 2664, 2665, 2666, 2667, 2668, 2669, 2670, 2671, 2672, 2673, 2674, 2675, 2676, 2677, 2678, 2679, 2680, 2681, 2682, 2683, 2684, 2685, 2686, 2687, 2688, 2689, 2690, 2691, 2692, 2693, 2694, 2695, 2696, 2697, 2698, 2699, 2700, 2701, 2702, 2703, 2704, 2705, 2706, 2707, 2708, 2709, 2710, 2711, 2712, 2713, 2714, 2715, 2716, 2717, 2718, 2719, 2720, 2721, 2722, 2723, 2724, 2725, 2726, 2727, 2728, 2729, 2730, 2731, 2732, 2733, 2734, 2735, 2736, 2737, 2738, 2739, 2740, 2741, 2742, 2743, 2744, 2745, 2746, 2747, 2748, 2749, 2750, 2751, 2752, 2753, 2754, 2755, 2756, 2757, 2758, 2759, 2760, 2761, 2762, 2763, 2764, 2765, 2766, 2767, 2768, 2769, 2770, 2771, 2772, 2773, 2774, 2775, 2776, 2777, 2778, 2779, 2780, 2781, 2782, 2783, 2784, 2785, 2786, 2787, 2788, 2789, 2790, 2791, 2792, 2793, 2794, 2795, 2796, 2797, 2798, 2799, 2800, 2801, 2802, 2803, 2804, 2805, 2806, 2807, 2808, 2809, 2810, 2811, 2812, 2813, 2814, 2815, 2816, 2817, 2818, 2819, 2820, 2821, 2822, 2823, 2824, 2825, 2826, 2827, 2828, 2829, 2830, 2831, 2832, 2833, 2834, 2835, 2836, 2837, 2838, 2839, 2840, 2841, 2842, 2843, 2844, 2845, 2846, 2847, 2848, 2849, 2850, 2851, 2852, 2853, 2854, 2855, 2856, 2857, 2858, 2859, 2860, 2861, 2862, 2863, 2864, 2865, 2866, 2867, 2868, 2869, 2870, 2871, 2872, 2873, 2874, 2875, 2876, 2877, 2878, 2879, 2880, 2881, 2882, 2883, 2884, 2885, 2886, 2887, 2888, 2889, 2890, 2891, 2892, 2893, 2894, 2895, 2896, 2897, 2898, 2899, 2900, 2901, 2902, 2903, 2904, 2905, 2906, 2907, 2908, 2909, 2910, 2911, 2912, 2913, 2914, 2915, 2916, 2917, 2918, 2919, 2920, 2921, 2922, 2923, 2924, 2925, 2926, 2927, 2928, 2929, 2930, 2931, 2932, 2933, 2934, 2935, 2936, 2937, 2938, 2939, 2940, 2941, 2942, 2943, 2944, 2945, 2946, 2947, 2948, 2949, 2950, 2951, 2952, 2953, 2954, 2955, 2956, 2957, 2958, 2959, 2960, 2961, 2962, 2963, 2964, 2965, 2966, 2967, 2968, 2969, 2970, 2971, 2972, 2973, 2974, 2975, 2976, 2977, 2978, 2979, 2980, 2981, 2982, 2983, 2984, 2985, 2986, 2987, 2988, 2989, 2990, 2991, 2992, 2993, 2994, 2995, 2996, 2997, 2998, 2999, 3000, 3001, 3002, 3003, 3004, 3005, 3006, 3007, 3008, 3009, 3010, 3011, 3012, 3013, 3014, 3015, 3016, 3017, 3018, 3019, 3020, 3021, 3022, 3023, 3024, 3025, 3026, 3027, 3028, 3029, 3030, 3031, 3032, 3033, 3034, 3035, 3036, 3037, 3038, 3039, 3040, 3041, 3042, 3043, 3044, 3045, 3046, 3047, 3048, 3049, 3050, 3051, 3052, 3053, 3054, 3055, 3056, 3057, 3058, 3059, 3060, 3061, 3062, 3063, 3064, 3065, 3066, 3067, 3068, 3069, 3070, 3071, 3072, 3073, 3074, 3075, 3076, 3077, 3078, 3079, 3080, 3081, 3082, 3083, 3084, 3085, 3086, 3087, 3088, 3089, 3090, 3091, 3092, 3093, 3094, 3095, 3096, 3097, 3098, 3099, 3100, 3101, 3102, 3103, 3104, 3105, 3106, 3107, 3108, 3109, 3110, 3111, 3112, 3113, 3114, 3115, 3116, 3117, 3118, 3119, 3120, 3121, 3122, 3123, 3124, 3125, 3126, 3127, 3128, 3129, 3130, 3131, 3132, 3133, 3134, 3135, 3136, 3137, 3138, 3139, 3140, 3141, 3142, 3143, 3144, 3145, 3146, 3147, 3148, 3149, 3150, 3151, 3152, 3153, 3154, 3155, 3156, 3157, 3158, 3159, 3160, 3161, 3162, 3163, 3164, 3165, 3166, 3167, 3168, 3169, 3170, 3171, 3172, 3173, 3174, 3175, 3176, 3177, 3178, 3179, 3180, 3181, 3182, 3183, 3184, 3185, 3186, 3187, 3188, 3189, 3190, 3191, 3192, 3193, 3194, 3195, 3196, 3197, 3198, 3199, 3200, 3201, 3202, 3203, 3204, 3205, 3206, 3207, 3208, 3209, 3210, 3211, 3212, 3213, 3214, 3215, 3216, 3217, 3218, 3219, 3220, 3221, 3222, 3223, 3224, 3225, 3226, 3227, 3228, 3229, 3230, 3231, 3232, 3233, 3234, 3235, 3236, 3237, 3238, 3239, 3240, 3241, 3242, 3243, 3244, 3245, 3246, 3247, 3248, 3249, 3250, 3251, 3252, 3253, 3254, 3255, 3256, 3257, 3258, 3259, 3260, 3261, 3262, 3263, 3264, 3265, 3266, 3267, 3268, 3269, 3270, 3271, 3272, 3273, 3274, 3275, 3276, 3277, 3278, 3279, 3280, 3281, 3282, 3283, 3284, 3285, 3286, 3287, 3288, 3289, 3290, 3291, 3292, 3293, 3294, 3295, 3296, 3297, 3298, 3299, 3300, 3301, 3302, 3303, 3304, 3305, 3306, 3307, 3308, 3309, 3310, 3311, 3312, 3313, 3314, 3315, 3316, 3317, 3318, 3319, 3320, 3321, 3322, 3323, 3324, 3325, 3326, 3327, 3328, 3329, 3330, 3331, 3332, 3333, 3334, 3335, 3336, 3337, 3338, 3339, 3340, 3341, 3342, 3343, 3344, 3345, 3346, 3347, 3348, 3349, 3350, 3351, 3352, 3353, 3354, 3355, 3356, 3357, 3358, 3359, 3360, 3361, 3362, 3363, 3364, 3365, 3366, 3367, 3368, 3369, 3370, 3371, 3372, 3373, 3374, 3375, 3376, 3377, 3378, 3379, 3380, 3381, 3382, 3383, 3384, 3385, 3386, 3387, 3388, 3389, 3390, 3391, 3392, 3393, 3394, 3395, 3396, 3397, 3398, 3399, 3400, 3401, 3402, 3403, 3404, 3405, 3406, 3407, 3408, 3409, 3410, 3411, 3412, 3413, 3414, 3415, 3416, 3417, 3418, 3419, 3420, 3421, 3422, 3423, 3424, 3425, 3426, 3427, 3428, 3429, 3430, 3431, 3432, 3433, 3434, 3435, 3436, 3437, 3438, 3439, 3440, 3441, 3442, 3443, 3444, 3445, 3446, 3447, 3448, 3449, 3450, 3451, 3452, 3453, 3454, 3455, 3456, 3457, 3458, 3459, 3460, 3461, 3462, 3463, 3464, 3465, 3466, 3467, 3468, 3469, 3470, 3471, 3472, 3473, 3474, 3475, 3476, 3477, 3478, 3479, 3480, 3481, 3482, 3483, 3484, 3485, 3486, 3487, 3488, 3489, 3490, 3491, 3492, 3493, 3494, 3495, 3496, 3497, 3498, 3499, 3500, 3501, 3502, 3503, 3504, 3505, 3506, 3507, 3508, 3509, 3510, 3511, 3512, 3513, 3514, 3515, 3516, 3517, 3518, 3519, 3520, 3521, 3522, 3523, 3524, 3525, 3526, 3527, 3528, 3529, 3530, 3531, 3532, 3533, 3534, 3535, 3536, 3537, 3538, 3539, 3540, 3541, 3542, 3543, 3544, 3545, 3546, 3547, 3548, 3549, 3550, 3551, 3552, 3553, 3554, 3555, 3556, 3557, 3558, 3559, 3560, 3561, 3562, 3563, 3564, 3565, 3566, 3567, 3568, 3569, 3570, 3571, 3572, 3573, 3574, 3575, 3576, 3577, 3578, 3579, 3580, 3581, 3582, 3583, 3584, 3585, 3586, 3587, 3588, 3589, 3590, 3591, 3592, 3593, 3594, 3595, 3596, 3597, 3598, 3599, 3600, 3601, 3602, 3603, 3604, 3605, 3606, 3607, 3608, 3609, 3610, 3611, 3612, 3613, 3614, 3615, 3616, 3617, 3618, 3619, 3620, 3621, 3622, 3623, 3624, 3625, 3626, 3627, 3628, 3629, 3630, 3631, 3632, 3633, 3634, 3635, 3636, 3637, 3638, 3639, 3640, 3641, 3642, 3643, 3644, 3645, 3646, 3647, 3648, 3649, 3650, 3651, 3652, 3653, 3654, 3655, 3656, 3657, 3658, 3659, 3660, 3661, 3662, 3663, 3664, 3665, 3666, 3667, 3668, 3669, 3670, 3671, 3672, 3673, 3674, 3675, 3676, 3677, 3678, 3679, 3680, 3681, 3682, 3683, 3684, 3685, 3686, 3687, 3688, 3689, 3690, 3691, 3692, 3693, 3694, 3695, 3696, 3697, 3698, 3699, 3700, 3701, 3702, 3703, 3704, 3705, 3706, 3707, 3708, 3709, 3710, 3711, 3712, 3713, 3714, 3715, 3716, 3717, 3718, 3719, 3720, 3721, 3722, 3723, 3724, 3725, 3726, 3727, 3728, 3729, 3730, 3731, 3732, 3733, 3734, 3735, 3736, 3737, 3738, 3739, 3740, 3741, 3742, 3743, 3744, 3745, 3746, 3747, 3748, 3749, 3750, 3751, 3752, 3753, 3754, 3755, 3756, 3757, 3758, 3759, 3760, 3761, 3762, 3763, 3764, 3765, 3766, 3767, 3768, 3769, 3770, 3771, 3772, 3773, 3774, 3775, 3776, 3777, 3778, 3779, 3780, 3781, 3782, 3783, 3784, 3785, 3786, 3787, 3788, 3789, 3790, 3791, 3792, 3793, 3794, 3795, 3796, 3797, 3798, 3799, 3800, 3801, 3802, 3803, 3804, 3805, 3806, 3807, 3808, 3809, 3810, 3811, 3812, 3813, 3814, 3815, 3816, 3817, 3818, 3819, 3820, 3821, 3822, 3823, 3824, 3825, 3826, 3827, 3828, 3829, 3830, 3831, 3832, 3833, 3834, 3835, 3836, 3837, 3838, 3839, 3840, 3841, 3842, 3843, 3844, 3845, 3846, 3847, 3848, 3849, 3850, 3851, 3852, 3853, 3854, 3855, 3856, 3857, 3858, 3859, 3860, 3861, 3862, 3863, 3864, 3865, 3866, 3867, 3868, 3869, 3870, 3871, 3872, 3873, 3874, 3875, 3876, 3877, 3878, 3879, 3880, 3881, 3882, 3883, 3884, 3885, 3886, 3887, 3888, 3889, 3890, 3891, 3892, 3893, 3894, 3895, 3896, 3897, 3898, 3899, 3900, 3901, 3902, 3903, 3904, 3905, 3906, 3907, 3908, 3909, 3910, 3911, 3912, 3913, 3914, 3915, 3916, 3917, 3918, 3919, 3920, 3921, 3922, 3923, 3924, 3925, 3926, 3927, 3928, 3929, 3930, 3931, 3932, 3933, 3934, 3935, 3936, 3937, 3938, 3939, 3940, 3941, 3942, 3943, 3944, 3945, 3946, 3947, 3948, 3949, 3950, 3951, 3952, 3953, 3954, 3955, 3956, 3957, 3958, 3959, 3960, 3961, 3962, 3963, 3964, 3965, 3966, 3967, 3968, 3969, 3970, 3971, 3972, 3973, 3974, 3975, 3976, 3977, 3978, 3979, 3980, 3981, 3982, 3983, 3984, 3985, 3986, 3987, 3988, 3989, 3990, 3991, 3992, 3993, 3994, 3995, 3996, 3997, 3998, 3999, 4000, 4001, 4002, 4003, 4004, 4005, 4006, 4007, 4008, 4009, 4010, 4011, 4012, 4013, 4014, 4015, 4016, 4017, 4018, 4019, 4020, 4021, 4022, 4023, 4024, 4025, 4026, 4027, 4028, 4029, 4030, 4031, 4032, 4033, 4034, 4035, 4036, 4037, 4038, 4039, 4040, 4041, 4042, 4043, 4044, 4045, 4046, 4047, 4048, 4049, 4050, 4051, 4052, 4053, 4054, 4055, 4056, 4057, 4058, 4059, 4060, 4061, 4062, 4063, 4064, 4065, 4066, 4067, 4068, 4069, 4070, 4071, 4072, 4073, 4074, 4075, 4076, 4077, 4078, 4079, 4080, 4081, 4082, 4083, 4084, 4085, 4086, 4087, 4088, 4089, 4090, 4091, 4092, 4093, 4094, 4095, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 256, 257, 258, 259, 260, 261, 262, 263, 264, 265, 266, 267, 268, 269, 270, 271, 272, 273, 274, 275, 276, 277, 278, 279, 280, 281, 282, 283, 284, 285, 286, 287, 288, 289, 290, 291, 292, 293, 294, 295, 296, 297, 298, 299, 300, 301, 302, 303, 304, 305, 306, 307, 308, 309, 310, 311, 312, 313, 314, 315, 316, 317, 318, 319, 320, 321, 322, 323, 324, 325, 326, 327, 328, 329, 330, 331, 332, 333, 334, 335, 336, 337, 338, 339, 340, 341, 342, 343, 344, 345, 346, 347, 348, 349, 350, 351, 352, 353, 354, 355, 356, 357, 358, 359, 360, 361, 362, 363, 364, 365, 366, 367, 368, 369, 370, 371, 372, 373, 374, 375, 376, 377, 378, 379, 380, 381, 382, 383, 384, 385, 386, 387, 388, 389, 390, 391, 392, 393, 394, 395, 396, 397, 398, 399, 400, 401, 402, 403, 404, 405, 406, 407, 408, 409, 410, 411, 412, 413, 414, 415, 416, 417, 418, 419, 420, 421, 422, 423, 424, 425, 426, 427, 428, 429, 430, 431, 432, 433, 434, 435, 436, 437, 438, 439, 440, 441, 442, 443, 444, 445, 446, 447, 448, 449, 450, 451, 452, 453, 454, 455, 456, 457, 458, 459, 460, 461, 462, 463, 464, 465, 466, 467, 468, 469, 470, 471, 472, 473, 474, 475, 476, 477, 478, 479, 480, 481, 482, 483, 484, 485, 486, 487, 488, 489, 490, 491, 492, 493, 494, 495, 496, 497, 498, 499, 500, 501, 502, 503, 504, 505, 506, 507, 508, 509, 510, 511, 512, 513, 514, 515, 516, 517, 518, 519, 520, 521, 522, 523, 524, 525, 526, 527, 528, 529, 530, 531, 532, 533, 534, 535, 536, 537, 538, 539, 540, 541, 542, 543, 544, 545, 546, 547, 548, 549, 550, 551, 552, 553, 554, 555, 556, 557, 558, 559, 560, 561, 562, 563, 564, 565, 566, 567, 568, 569, 570, 571, 572, 573, 574, 575, 576, 577, 578, 579, 580, 581, 582, 583, 584, 585, 586, 587, 588, 589, 590, 591, 592, 593, 594, 595, 596, 597, 598, 599, 600, 601, 602, 603, 604, 605, 606, 607, 608, 609, 610, 611, 612, 613, 614, 615, 616, 617, 618, 619, 620, 621, 622, 623, 624, 625, 626, 627, 628, 629, 630, 631, 632, 633, 634, 635, 636, 637, 638, 639, 640, 641, 642, 643, 644, 645, 646, 647, 648, 649, 650, 651, 652, 653, 654, 655, 656, 657, 658, 659, 660, 661, 662, 663, 664, 665, 666, 667, 668, 669, 670, 671, 672, 673, 674, 675, 676, 677, 678, 679, 680, 681, 682, 683, 684, 685, 686, 687, 688, 689, 690, 691, 692, 693, 694, 695, 696, 697, 698, 699, 700, 701, 702, 703, 704, 705, 706, 707, 708, 709, 710, 711, 712, 713, 714, 715, 716, 717, 718, 719, 720, 721, 722, 723, 724, 725, 726, 727, 728, 729, 730, 731, 732, 733, 734, 735, 736, 737, 738, 739, 740, 741, 742, 743, 744, 745, 746, 747, 748, 749, 750, 751, 752, 753, 754, 755, 756, 757, 758, 759, 760, 761, 762, 763, 764, 765, 766, 767, 768, 769, 770, 771, 772, 773, 774, 775, 776, 777, 778, 779, 780, 781, 782, 783, 784, 785, 786, 787, 788, 789, 790, 791, 792, 793, 794, 795, 796, 797, 798, 799, 800, 801, 802, 803, 804, 805, 806, 807, 808, 809, 810, 811, 812, 813, 814, 815, 816, 817, 818, 819, 820, 821, 822, 823, 824, 825, 826, 827, 828, 829, 830, 831, 832, 833, 834, 835, 836, 837, 838, 839, 840, 841, 842, 843, 844, 845, 846, 847, 848, 849, 850, 851, 852, 853, 854, 855, 856, 857, 858, 859, 860, 861, 862, 863, 864, 865, 866, 867, 868, 869, 870, 871, 872, 873, 874, 875, 876, 877, 878, 879, 880, 881, 882, 883, 884, 885, 886, 887, 888, 889, 890, 891, 892, 893, 894, 895, 896, 897, 898, 899, 900, 901, 902, 903, 904, 905, 906, 907, 908, 909, 910, 911, 912, 913, 914, 915, 916, 917, 918, 919, 920, 921, 922, 923, 924, 925, 926, 927, 928, 929, 930, 931, 932, 933, 934, 935, 936, 937, 938, 939, 940, 941, 942, 943, 944, 945, 946, 947, 948, 949, 950, 951, 952, 953, 954, 955, 956, 957, 958, 959, 960, 961, 962, 963, 964, 965, 966, 967, 968, 969, 970, 971, 972, 973, 974, 975, 976, 977, 978, 979, 980, 981, 982, 983, 984, 985, 986, 987, 988, 989, 990, 991, 992, 993, 994, 995, 996, 997, 998, 999, 1000, 1001, 1002, 1003, 1004, 1005, 1006, 1007, 1008, 1009, 1010, 1011, 1012, 1013, 1014, 1015, 1016, 1017, 1018, 1019, 1020, 1021, 1022, 1023, 1024, 1025, 1026, 1027, 1028, 1029, 1030, 1031, 1032, 1033, 1034, 1035, 1036, 1037, 1038, 1039, 1040, 1041, 1042, 1043, 1044, 1045, 1046, 1047, 1048, 1049, 1050, 1051, 1052, 1053, 1054, 1055, 1056, 1057, 1058, 1059, 1060, 1061, 1062, 1063, 1064, 1065, 1066, 1067, 1068, 1069, 1070, 1071, 1072, 1073, 1074, 1075, 1076, 1077, 1078, 1079, 1080, 1081, 1082, 1083, 1084, 1085, 1086, 1087, 1088, 1089, 1090, 1091, 1092, 1093, 1094, 1095, 1096, 1097, 1098, 1099, 1100, 1101, 1102, 1103, 1104, 1105, 1106, 1107, 1108, 1109, 1110, 1111, 1112, 1113, 1114, 1115, 1116, 1117, 1118, 1119, 1120, 1121, 1122, 1123, 1124, 1125, 1126, 1127, 1128, 1129, 1130, 1131, 1132, 1133, 1134, 1135, 1136, 1137, 1138, 1139, 1140, 1141, 1142, 1143, 1144, 1145, 1146, 1147, 1148, 1149, 1150, 1151, 1152, 1153, 1154, 1155, 1156, 1157, 1158, 1159, 1160, 1161, 1162, 1163, 1164, 1165, 1166, 1167, 1168, 1169, 1170, 1171, 1172, 1173, 1174, 1175, 1176, 1177, 1178, 1179, 1180, 1181, 1182, 1183, 1184, 1185, 1186, 1187, 1188, 1189, 1190, 1191, 1192, 1193, 1194, 1195, 1196, 1197, 1198, 1199, 1200, 1201, 1202, 1203, 1204, 1205, 1206, 1207, 1208, 1209, 1210, 1211, 1212, 1213, 1214, 1215, 1216, 1217, 1218, 1219, 1220, 1221, 1222, 1223, 1224, 1225, 1226, 1227, 1228, 1229, 1230, 1231, 1232, 1233, 1234, 1235, 1236, 1237, 1238, 1239, 1240, 1241, 1242, 1243, 1244, 1245, 1246, 1247, 1248, 1249, 1250, 1251, 1252, 1253, 1254, 1255, 1256, 1257, 1258, 1259, 1260, 1261, 1262, 1263, 1264, 1265, 1266, 1267, 1268, 1269, 1270, 1271, 1272, 1273, 1274, 1275, 1276, 1277, 1278, 1279, 1280, 1281, 1282, 1283, 1284, 1285, 1286, 1287, 1288, 1289, 1290, 1291, 1292, 1293, 1294, 1295, 1296, 1297, 1298, 1299, 1300, 1301, 1302, 1303, 1304, 1305, 1306, 1307, 1308, 1309, 1310, 1311, 1312, 1313, 1314, 1315, 1316, 1317, 1318, 1319, 1320, 1321, 1322, 1323, 1324, 1325, 1326, 1327, 1328, 1329, 1330, 1331, 1332, 1333, 1334, 1335, 1336, 1337, 1338, 1339, 1340, 1341, 1342, 1343, 1344, 1345, 1346, 1347, 1348, 1349, 1350, 1351, 1352, 1353, 1354, 1355, 1356, 1357, 1358, 1359, 1360, 1361, 1362, 1363, 1364, 1365, 1366, 1367, 1368, 1369, 1370, 1371, 1372, 1373, 1374, 1375, 1376, 1377, 1378, 1379, 1380, 1381, 1382, 1383, 1384, 1385, 1386, 1387, 1388, 1389, 1390, 1391, 1392, 1393, 1394, 1395, 1396, 1397, 1398, 1399, 1400, 1401, 1402, 1403, 1404, 1405, 1406, 1407, 1408, 1409, 1410, 1411, 1412, 1413, 1414, 1415, 1416, 1417, 1418, 1419, 1420, 1421, 1422, 1423, 1424, 1425, 1426, 1427, 1428, 1429, 1430, 1431, 1432, 1433, 1434, 1435, 1436, 1437, 1438, 1439, 1440, 1441, 1442, 1443, 1444, 1445, 1446, 1447, 1448, 1449, 1450, 1451, 1452, 1453, 1454, 1455, 1456, 1457, 1458, 1459, 1460, 1461, 1462, 1463, 1464, 1465, 1466, 1467, 1468, 1469, 1470, 1471, 1472, 1473, 1474, 1475, 1476, 1477, 1478, 1479, 1480, 1481, 1482, 1483, 1484, 1485, 1486, 1487, 1488, 1489, 1490, 1491, 1492, 1493, 1494, 1495, 1496, 1497, 1498, 1499, 1500, 1501, 1502, 1503, 1504, 1505, 1506, 1507, 1508, 1509, 1510, 1511, 1512, 1513, 1514, 1515, 1516, 1517, 1518, 1519, 1520, 1521, 1522, 1523, 1524, 1525, 1526, 1527, 1528, 1529, 1530, 1531, 1532, 1533, 1534, 1535, 1536, 1537, 1538, 1539, 1540, 1541, 1542, 1543, 1544, 1545, 1546, 1547, 1548, 1549, 1550, 1551, 1552, 1553, 1554, 1555, 1556, 1557, 1558, 1559, 1560, 1561, 1562, 1563, 1564, 1565, 1566, 1567, 1568, 1569, 1570, 1571, 1572, 1573, 1574, 1575, 1576, 1577, 1578, 1579, 1580, 1581, 1582, 1583, 1584, 1585, 1586, 1587, 1588, 1589, 1590, 1591, 1592, 1593, 1594, 1595, 1596, 1597, 1598, 1599, 1600, 1601, 1602, 1603, 1604, 1605, 1606, 1607, 1608, 1609, 1610, 1611, 1612, 1613, 1614, 1615, 1616, 1617, 1618, 1619, 1620, 1621, 1622, 1623, 1624, 1625, 1626, 1627, 1628, 1629, 1630, 1631, 1632, 1633, 1634, 1635, 1636, 1637, 1638, 1639, 1640, 1641, 1642, 1643, 1644, 1645, 1646, 1647, 1648, 1649, 1650, 1651, 1652, 1653, 1654, 1655, 1656, 1657, 1658, 1659, 1660, 1661, 1662, 1663, 1664, 1665, 1666, 1667, 1668, 1669, 1670, 1671, 1672, 1673, 1674, 1675, 1676, 1677, 1678, 1679, 1680, 1681, 1682, 1683, 1684, 1685, 1686, 1687, 1688, 1689, 1690, 1691, 1692, 1693, 1694, 1695, 1696, 1697, 1698, 1699, 1700, 1701, 1702, 1703, 1704, 1705, 1706, 1707, 1708, 1709, 1710, 1711, 1712, 1713, 1714, 1715, 1716, 1717, 1718, 1719, 1720, 1721, 1722, 1723, 1724, 1725, 1726, 1727, 1728, 1729, 1730, 1731, 1732, 1733, 1734, 1735, 1736, 1737, 1738, 1739, 1740, 1741, 1742, 1743, 1744, 1745, 1746, 1747, 1748, 1749, 1750, 1751, 1752, 1753, 1754, 1755, 1756, 1757, 1758, 1759, 1760, 1761, 1762, 1763, 1764, 1765, 1766, 1767, 1768, 1769, 1770, 1771, 1772, 1773, 1774, 1775, 1776, 1777, 1778, 1779, 1780, 1781, 1782, 1783, 1784, 1785, 1786, 1787, 1788, 1789, 1790, 1791, 1792, 1793, 1794, 1795, 1796, 1797, 1798, 1799, 1800, 1801, 1802, 1803, 1804, 1805, 1806, 1807, 1808, 1809, 1810, 1811, 1812, 1813, 1814, 1815, 1816, 1817, 1818, 1819, 1820, 1821, 1822, 1823, 1824, 1825, 1826, 1827, 1828, 1829, 1830, 1831, 1832, 1833, 1834, 1835, 1836, 1837, 1838, 1839, 1840, 1841, 1842, 1843, 1844, 1845, 1846, 1847, 1848, 1849, 1850, 1851, 1852, 1853, 1854, 1855, 1856, 1857, 1858, 1859, 1860, 1861, 1862, 1863, 1864, 1865, 1866, 1867, 1868, 1869, 1870, 1871, 1872, 1873, 1874, 1875, 1876, 1877, 1878, 1879, 1880, 1881, 1882, 1883, 1884, 1885, 1886, 1887, 1888, 1889, 1890, 1891, 1892, 1893, 1894, 1895, 1896, 1897, 1898, 1899, 1900, 1901, 1902, 1903, 1904, 1905, 1906, 1907, 1908, 1909, 1910, 1911, 1912, 1913, 1914, 1915, 1916, 1917, 1918, 1919, 1920, 1921, 1922, 1923, 1924, 1925, 1926, 1927, 1928, 1929, 1930, 1931, 1932, 1933, 1934, 1935, 1936, 1937, 1938, 1939, 1940, 1941, 1942, 1943, 1944, 1945, 1946, 1947, 1948, 1949, 1950, 1951, 1952, 1953, 1954, 1955, 1956, 1957, 1958, 1959, 1960, 1961, 1962, 1963, 1964, 1965, 1966, 1967, 1968, 1969, 1970, 1971, 1972, 1973, 1974, 1975, 1976, 1977, 1978, 1979, 1980, 1981, 1982, 1983, 1984, 1985, 1986, 1987, 1988, 1989, 1990, 1991, 1992, 1993, 1994, 1995, 1996, 1997, 1998, 1999, 2000, 2001, 2002, 2003, 2004, 2005, 2006, 2007, 2008, 2009, 2010, 2011, 2012, 2013, 2014, 2015, 2016, 2017, 2018, 2019, 2020, 2021, 2022, 2023, 2024, 2025, 2026, 2027, 2028, 2029, 2030, 2031, 2032, 2033, 2034, 2035, 2036, 2037, 2038, 2039, 2040, 2041, 2042, 2043, 2044, 2045, 2046, 2047, 2048, 2049, 2050, 2051, 2052, 2053, 2054, 2055, 2056, 2057, 2058, 2059, 2060, 2061, 2062, 2063, 2064, 2065, 2066, 2067, 2068, 2069, 2070, 2071, 2072, 2073, 2074, 2075, 2076, 2077, 2078, 2079, 2080, 2081, 2082, 2083, 2084, 2085, 2086, 2087, 2088, 2089, 2090, 2091, 2092, 2093, 2094, 2095, 2096, 2097, 2098, 2099, 2100, 2101, 2102, 2103, 2104, 2105, 2106, 2107, 2108, 2109, 2110, 2111, 2112, 2113, 2114, 2115, 2116, 2117, 2118, 2119, 2120, 2121, 2122, 2123, 2124, 2125, 2126, 2127, 2128, 2129, 2130, 2131, 2132, 2133, 2134, 2135, 2136, 2137, 2138, 2139, 2140, 2141, 2142, 2143, 2144, 2145, 2146, 2147, 2148, 2149, 2150, 2151, 2152, 2153, 2154, 2155, 2156, 2157, 2158, 2159, 2160, 2161, 2162, 2163, 2164, 2165, 2166, 2167, 2168, 2169, 2170, 2171, 2172, 2173, 2174, 2175, 2176, 2177, 2178, 2179, 2180, 2181, 2182, 2183, 2184, 2185, 2186, 2187, 2188, 2189, 2190, 2191, 2192, 2193, 2194, 2195, 2196, 2197, 2198, 2199, 2200, 2201, 2202, 2203, 2204, 2205, 2206, 2207, 2208, 2209, 2210, 2211, 2212, 2213, 2214, 2215, 2216, 2217, 2218, 2219, 2220, 2221, 2222, 2223, 2224, 2225, 2226, 2227, 2228, 2229, 2230, 2231, 2232, 2233, 2234, 2235, 2236, 2237, 2238, 2239, 2240, 2241, 2242, 2243, 2244, 2245, 2246, 2247, 2248, 2249, 2250, 2251, 2252, 2253, 2254, 2255, 2256, 2257, 2258, 2259, 2260, 2261, 2262, 2263, 2264, 2265, 2266, 2267, 2268, 2269, 2270, 2271, 2272, 2273, 2274, 2275, 2276, 2277, 2278, 2279, 2280, 2281, 2282, 2283, 2284, 2285, 2286, 2287, 2288, 2289, 2290, 2291, 2292, 2293, 2294, 2295, 2296, 2297, 2298, 2299, 2300, 2301, 2302, 2303, 2304, 2305, 2306, 2307, 2308, 2309, 2310, 2311, 2312, 2313, 2314, 2315, 2316, 2317, 2318, 2319, 2320, 2321, 2322, 2323, 2324, 2325, 2326, 2327, 2328, 2329, 2330, 2331, 2332, 2333, 2334, 2335, 2336, 2337, 2338, 2339, 2340, 2341, 2342, 2343, 2344, 2345, 2346, 2347, 2348, 2349, 2350, 2351, 2352, 2353, 2354, 2355, 2356, 2357, 2358, 2359, 2360, 2361, 2362, 2363, 2364, 2365, 2366, 2367, 2368, 2369, 2370, 2371, 2372, 2373, 2374, 2375, 2376, 2377, 2378, 2379, 2380, 2381, 2382, 2383, 2384, 2385, 2386, 2387, 2388, 2389, 2390, 2391, 2392, 2393, 2394, 2395, 2396, 2397, 2398, 2399, 2400, 2401, 2402, 2403, 2404, 2405, 2406, 2407, 2408, 2409, 2410, 2411, 2412, 2413, 2414, 2415, 2416, 2417, 2418, 2419, 2420, 2421, 2422, 2423, 2424, 2425, 2426, 2427, 2428, 2429, 2430, 2431, 2432, 2433, 2434, 2435, 2436, 2437, 2438, 2439, 2440, 2441, 2442, 2443, 2444, 2445, 2446, 2447, 2448, 2449, 2450, 2451, 2452, 2453, 2454, 2455, 2456, 2457, 2458, 2459, 2460, 2461, 2462, 2463, 2464, 2465, 2466, 2467, 2468, 2469, 2470, 2471, 2472, 2473, 2474, 2475, 2476, 2477, 2478, 2479, 2480, 2481, 2482, 2483, 2484, 2485, 2486, 2487, 2488, 2489, 2490, 2491, 2492, 2493, 2494, 2495, 2496, 2497, 2498, 2499, 2500, 2501, 2502, 2503, 2504, 2505, 2506, 2507, 2508, 2509, 2510, 2511, 2512, 2513, 2514, 2515, 2516, 2517, 2518, 2519, 2520, 2521, 2522, 2523, 2524, 2525, 2526, 2527, 2528, 2529, 2530, 2531, 2532, 2533, 2534, 2535, 2536, 2537, 2538, 2539, 2540, 2541, 2542, 2543, 2544, 2545, 2546, 2547, 2548, 2549, 2550, 2551, 2552, 2553, 2554, 2555, 2556, 2557, 2558, 2559, 2560, 2561, 2562, 2563, 2564, 2565, 2566, 2567, 2568, 2569, 2570, 2571, 2572, 2573, 2574, 2575, 2576, 2577, 2578, 2579, 2580, 2581, 2582, 2583, 2584, 2585, 2586, 2587, 2588, 2589, 2590, 2591, 2592, 2593, 2594, 2595, 2596, 2597, 2598, 2599, 2600, 2601, 2602, 2603, 2604, 2605, 2606, 2607, 2608, 2609, 2610, 2611, 2612, 2613, 2614, 2615, 2616, 2617, 2618, 2619, 2620, 2621, 2622, 2623, 2624, 2625, 2626, 2627, 2628, 2629, 2630, 2631, 2632, 2633, 2634, 2635, 2636, 2637, 2638, 2639, 2640, 2641, 2642, 2643, 2644, 2645, 2646, 2647, 2648, 2649, 2650, 2651, 2652, 2653, 2654, 2655, 2656, 2657, 2658, 2659, 2660, 2661, 2662, 2663, 2664, 2665, 2666, 2667, 2668, 2669, 2670, 2671, 2672, 2673, 2674, 2675, 2676, 2677, 2678, 2679, 2680, 2681, 2682, 2683, 2684, 2685, 2686, 2687, 2688, 2689, 2690, 2691, 2692, 2693, 2694, 2695, 2696, 2697, 2698, 2699, 2700, 2701, 2702, 2703, 2704, 2705, 2706, 2707, 2708, 2709, 2710, 2711, 2712, 2713, 2714, 2715, 2716, 2717, 2718, 2719, 2720, 2721, 2722, 2723, 2724, 2725, 2726, 2727, 2728, 2729, 2730, 2731, 2732, 2733, 2734, 2735, 2736, 2737, 2738, 2739, 2740, 2741, 2742, 2743, 2744, 2745, 2746, 2747, 2748, 2749, 2750, 2751, 2752, 2753, 2754, 2755, 2756, 2757, 2758, 2759, 2760, 2761, 2762, 2763, 2764, 2765, 2766, 2767, 2768, 2769, 2770, 2771, 2772, 2773, 2774, 2775, 2776, 2777, 2778, 2779, 2780, 2781, 2782, 2783, 2784, 2785, 2786, 2787, 2788, 2789, 2790, 2791, 2792, 2793, 2794, 2795, 2796, 2797, 2798, 2799, 2800, 2801, 2802, 2803, 2804, 2805, 2806, 2807, 2808, 2809, 2810, 2811, 2812, 2813, 2814, 2815, 2816, 2817, 2818, 2819, 2820, 2821, 2822, 2823, 2824, 2825, 2826, 2827, 2828, 2829, 2830, 2831, 2832, 2833, 2834, 2835, 2836, 2837, 2838, 2839, 2840, 2841, 2842, 2843, 2844, 2845, 2846, 2847, 2848, 2849, 2850, 2851, 2852, 2853, 2854, 2855, 2856, 2857, 2858, 2859, 2860, 2861, 2862, 2863, 2864, 2865, 2866, 2867, 2868, 2869, 2870, 2871, 2872, 2873, 2874, 2875, 2876, 2877, 2878, 2879, 2880, 2881, 2882, 2883, 2884, 2885, 2886, 2887, 2888, 2889, 2890, 2891, 2892, 2893, 2894, 2895, 2896, 2897, 2898, 2899, 2900, 2901, 2902, 2903, 2904, 2905, 2906, 2907, 2908, 2909, 2910, 2911, 2912, 2913, 2914, 2915, 2916, 2917, 2918, 2919, 2920, 2921, 2922, 2923, 2924, 2925, 2926, 2927, 2928, 2929, 2930, 2931, 2932, 2933, 2934, 2935, 2936, 2937, 2938, 2939, 2940, 2941, 2942, 2943, 2944, 2945, 2946, 2947, 2948, 2949, 2950, 2951, 2952, 2953, 2954, 2955, 2956, 2957, 2958, 2959, 2960, 2961, 2962, 2963, 2964, 2965, 2966, 2967, 2968, 2969, 2970, 2971, 2972, 2973, 2974, 2975, 2976, 2977, 2978, 2979, 2980, 2981, 2982, 2983, 2984, 2985, 2986, 2987, 2988, 2989, 2990, 2991, 2992, 2993, 2994, 2995, 2996, 2997, 2998, 2999, 3000, 3001, 3002, 3003, 3004, 3005, 3006, 3007, 3008, 3009, 3010, 3011, 3012, 3013, 3014, 3015, 3016, 3017, 3018, 3019, 3020, 3021, 3022, 3023, 3024, 3025, 3026, 3027, 3028, 3029, 3030, 3031, 3032, 3033, 3034, 3035, 3036, 3037, 3038, 3039, 3040, 3041, 3042, 3043, 3044, 3045, 3046, 3047, 3048, 3049, 3050, 3051, 3052, 3053, 3054, 3055, 3056, 3057, 3058, 3059, 3060, 3061, 3062, 3063, 3064, 3065, 3066, 3067, 3068, 3069, 3070, 3071, 3072, 3073, 3074, 3075, 3076, 3077, 3078, 3079, 3080, 3081, 3082, 3083, 3084, 3085, 3086, 3087, 3088, 3089, 3090, 3091, 3092, 3093, 3094, 3095, 3096, 3097, 3098, 3099, 3100, 3101, 3102, 3103, 3104, 3105, 3106, 3107, 3108, 3109, 3110, 3111, 3112, 3113, 3114, 3115, 3116, 3117, 3118, 3119, 3120, 3121, 3122, 3123, 3124, 3125, 3126, 3127, 3128, 3129, 3130, 3131, 3132, 3133, 3134, 3135, 3136, 3137, 3138, 3139, 3140, 3141, 3142, 3143, 3144, 3145, 3146, 3147, 3148, 3149, 3150, 3151, 3152, 3153, 3154, 3155, 3156, 3157, 3158, 3159, 3160, 3161, 3162, 3163, 3164, 3165, 3166, 3167, 3168, 3169, 3170, 3171, 3172, 3173, 3174, 3175, 3176, 3177, 3178, 3179, 3180, 3181, 3182, 3183, 3184, 3185, 3186, 3187, 3188, 3189, 3190, 3191, 3192, 3193, 3194, 3195, 3196, 3197, 3198, 3199, 3200, 3201, 3202, 3203, 3204, 3205, 3206, 3207, 3208, 3209, 3210, 3211, 3212, 3213, 3214, 3215, 3216, 3217, 3218, 3219, 3220, 3221, 3222, 3223, 3224, 3225, 3226, 3227, 3228, 3229, 3230, 3231, 3232, 3233, 3234, 3235, 3236, 3237, 3238, 3239, 3240, 3241, 3242, 3243, 3244, 3245, 3246, 3247, 3248, 3249, 3250, 3251, 3252, 3253, 3254, 3255, 3256, 3257, 3258, 3259, 3260, 3261, 3262, 3263, 3264, 3265, 3266, 3267, 3268, 3269, 3270, 3271, 3272, 3273, 3274, 3275, 3276, 3277, 3278, 3279, 3280, 3281, 3282, 3283, 3284, 3285, 3286, 3287, 3288, 3289, 3290, 3291, 3292, 3293, 3294, 3295, 3296, 3297, 3298, 3299, 3300, 3301, 3302, 3303, 3304, 3305, 3306, 3307, 3308, 3309, 3310, 3311, 3312, 3313, 3314, 3315, 3316, 3317, 3318, 3319, 3320, 3321, 3322, 3323, 3324, 3325, 3326, 3327, 3328, 3329, 3330, 3331, 3332, 3333, 3334, 3335, 3336, 3337, 3338, 3339, 3340, 3341, 3342, 3343, 3344, 3345, 3346, 3347, 3348, 3349, 3350, 3351, 3352, 3353, 3354, 3355, 3356, 3357, 3358, 3359, 3360, 3361, 3362, 3363, 3364, 3365, 3366, 3367, 3368, 3369, 3370, 3371, 3372, 3373, 3374, 3375, 3376, 3377, 3378, 3379, 3380, 3381, 3382, 3383, 3384, 3385, 3386, 3387, 3388, 3389, 3390, 3391, 3392, 3393, 3394, 3395, 3396, 3397, 3398, 3399, 3400, 3401, 3402, 3403, 3404, 3405, 3406, 3407, 3408, 3409, 3410, 3411, 3412, 3413, 3414, 3415, 3416, 3417, 3418, 3419, 3420, 3421, 3422, 3423, 3424, 3425, 3426, 3427, 3428, 3429, 3430, 3431, 3432, 3433, 3434, 3435, 3436, 3437, 3438, 3439, 3440, 3441, 3442, 3443, 3444, 3445, 3446, 3447, 3448, 3449, 3450, 3451, 3452, 3453, 3454, 3455, 3456, 3457, 3458, 3459, 3460, 3461, 3462, 3463, 3464, 3465, 3466, 3467, 3468, 3469, 3470, 3471, 3472, 3473, 3474, 3475, 3476, 3477, 3478, 3479, 3480, 3481, 3482, 3483, 3484, 3485, 3486, 3487, 3488, 3489, 3490, 3491, 3492, 3493, 3494, 3495, 3496, 3497, 3498, 3499, 3500, 3501, 3502, 3503, 3504, 3505, 3506, 3507, 3508, 3509, 3510, 3511, 3512, 3513, 3514, 3515, 3516, 3517, 3518, 3519, 3520, 3521, 3522, 3523, 3524, 3525, 3526, 3527, 3528, 3529, 3530, 3531, 3532, 3533, 3534, 3535, 3536, 3537, 3538, 3539, 3540, 3541, 3542, 3543, 3544, 3545, 3546, 3547, 3548, 3549, 3550, 3551, 3552, 3553, 3554, 3555, 3556, 3557, 3558, 3559, 3560, 3561, 3562, 3563, 3564, 3565, 3566, 3567, 3568, 3569, 3570, 3571, 3572, 3573, 3574, 3575, 3576, 3577, 3578, 3579, 3580, 3581, 3582, 3583, 3584, 3585, 3586, 3587, 3588, 3589, 3590, 3591, 3592, 3593, 3594, 3595, 3596, 3597, 3598, 3599, 3600, 3601, 3602, 3603, 3604, 3605, 3606, 3607, 3608, 3609, 3610, 3611, 3612, 3613, 3614, 3615, 3616, 3617, 3618, 3619, 3620, 3621, 3622, 3623, 3624, 3625, 3626, 3627, 3628, 3629, 3630, 3631, 3632, 3633, 3634, 3635, 3636, 3637, 3638, 3639, 3640, 3641, 3642, 3643, 3644, 3645, 3646, 3647, 3648, 3649, 3650, 3651, 3652, 3653, 3654, 3655, 3656, 3657, 3658, 3659, 3660, 3661, 3662, 3663, 3664, 3665, 3666, 3667, 3668, 3669, 3670, 3671, 3672, 3673, 3674, 3675, 3676, 3677, 3678, 3679, 3680, 3681, 3682, 3683, 3684, 3685, 3686, 3687, 3688, 3689, 3690, 3691, 3692, 3693, 3694, 3695, 3696, 3697, 3698, 3699, 3700, 3701, 3702, 3703, 3704, 3705, 3706, 3707, 3708, 3709, 3710, 3711, 3712, 3713, 3714, 3715, 3716, 3717, 3718, 3719, 3720, 3721, 3722, 3723, 3724, 3725, 3726, 3727, 3728, 3729, 3730, 3731, 3732, 3733, 3734, 3735, 3736, 3737, 3738, 3739, 3740, 3741, 3742, 3743, 3744, 3745, 3746, 3747, 3748, 3749, 3750, 3751, 3752, 3753, 3754, 3755, 3756, 3757, 3758, 3759, 3760, 3761, 3762, 3763, 3764, 3765, 3766, 3767, 3768, 3769, 3770, 3771, 3772, 3773, 3774, 3775, 3776, 3777, 3778, 3779, 3780, 3781, 3782, 3783, 3784, 3785, 3786, 3787, 3788, 3789, 3790, 3791, 3792, 3793, 3794, 3795, 3796, 3797, 3798, 3799, 3800, 3801, 3802, 3803, 3804, 3805, 3806, 3807, 3808, 3809, 3810, 3811, 3812, 3813, 3814, 3815, 3816, 3817, 3818, 3819, 3820, 3821, 3822, 3823, 3824, 3825, 3826, 3827, 3828, 3829, 3830, 3831, 3832, 3833, 3834, 3835, 3836, 3837, 3838, 3839, 3840, 3841, 3842, 3843, 3844, 3845, 3846, 3847, 3848, 3849, 3850, 3851, 3852, 3853, 3854, 3855, 3856, 3857, 3858, 3859, 3860, 3861, 3862, 3863, 3864, 3865, 3866, 3867, 3868, 3869, 3870, 3871, 3872, 3873, 3874, 3875, 3876, 3877, 3878, 3879, 3880, 3881, 3882, 3883, 3884, 3885, 3886, 3887, 3888, 3889, 3890, 3891, 3892, 3893, 3894, 3895, 3896, 3897, 3898, 3899, 3900, 3901, 3902, 3903, 3904, 3905, 3906, 3907, 3908, 3909, 3910, 3911, 3912, 3913, 3914, 3915, 3916, 3917, 3918, 3919, 3920, 3921, 3922, 3923, 3924, 3925, 3926, 3927, 3928, 3929, 3930, 3931, 3932, 3933, 3934, 3935, 3936, 3937, 3938, 3939, 3940, 3941, 3942, 3943, 3944, 3945, 3946, 3947, 3948, 3949, 3950, 3951, 3952, 3953, 3954, 3955, 3956, 3957, 3958, 3959, 3960, 3961, 3962, 3963, 3964, 3965, 3966, 3967, 3968, 3969, 3970, 3971, 3972, 3973, 3974, 3975, 3976, 3977, 3978, 3979, 3980, 3981, 3982, 3983, 3984, 3985, 3986, 3987, 3988, 3989, 3990, 3991, 3992, 3993, 3994, 3995, 3996, 3997, 3998, 3999, 4000, 4001, 4002, 4003, 4004, 4005, 4006, 4007, 4008, 4009, 4010, 4011, 4012, 4013, 4014, 4015, 4016, 4017, 4018, 4019, 4020, 4021, 4022, 4023, 4024, 4025, 4026, 4027, 4028, 4029, 4030, 4031, 4032, 4033, 4034, 4035, 4036, 4037, 4038, 4039, 4040, 4041, 4042, 4043, 4044, 4045, 4046, 4047, 4048, 4049, 4050, 4051, 4052, 4053, 4054, 4055, 4056, 4057, 4058, 4059, 4060, 4061, 4062, 4063, 4064, 4065, 4066, 4067, 4068, 4069, 4070, 4071, 4072, 4073, 4074, 4075, 4076, 4077, 4078, 4079, 4080, 4081, 4082, 4083, 4084, 4085, 4086, 4087, 4088, 4089, 4090, 4091, 4092, 4093, 4094, 4095, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 256, 257, 258, 259, 260, 261, 262, 263, 264, 265, 266, 267, 268, 269, 270, 271, 272, 273, 274, 275, 276, 277, 278, 279, 280, 281, 282, 283, 284, 285, 286, 287, 288, 289, 290, 291, 292, 293, 294, 295, 296, 297, 298, 299, 300, 301, 302, 303, 304, 305, 306, 307, 308, 309, 310, 311, 312, 313, 314, 315, 316, 317, 318, 319, 320, 321, 322, 323, 324, 325, 326, 327, 328, 329, 330, 331, 332, 333, 334, 335, 336, 337, 338, 339, 340, 341, 342, 343, 344, 345, 346, 347, 348, 349, 350, 351, 352, 353, 354, 355, 356, 357, 358, 359, 360, 361, 362, 363, 364, 365, 366, 367, 368, 369, 370, 371, 372, 373, 374, 375, 376, 377, 378, 379, 380, 381, 382, 383, 384, 385, 386, 387, 388, 389, 390, 391, 392, 393, 394, 395, 396, 397, 398, 399, 400, 401, 402, 403, 404, 405, 406, 407, 408, 409, 410, 411, 412, 413, 414, 415, 416, 417, 418, 419, 420, 421, 422, 423, 424, 425, 426, 427, 428, 429, 430, 431, 432, 433, 434, 435, 436, 437, 438, 439, 440, 441, 442, 443, 444, 445, 446, 447, 448, 449, 450, 451, 452, 453, 454, 455, 456, 457, 458, 459, 460, 461, 462, 463, 464, 465, 466, 467, 468, 469, 470, 471, 472, 473, 474, 475, 476, 477, 478, 479, 480, 481, 482, 483, 484, 485, 486, 487, 488, 489, 490, 491, 492, 493, 494, 495, 496, 497, 498, 499, 500, 501, 502, 503, 504, 505, 506, 507, 508, 509, 510, 511, 512, 513, 514, 515, 516, 517, 518, 519, 520, 521, 522, 523, 524, 525, 526, 527, 528, 529, 530, 531, 532, 533, 534, 535, 536, 537, 538, 539, 540, 541, 542, 543, 544, 545, 546, 547, 548, 549, 550, 551, 552, 553, 554, 555, 556, 557, 558, 559, 560, 561, 562, 563, 564, 565, 566, 567, 568, 569, 570, 571, 572, 573, 574, 575, 576, 577, 578, 579, 580, 581, 582, 583, 584, 585, 586, 587, 588, 589, 590, 591, 592, 593, 594, 595, 596, 597, 598, 599, 600, 601, 602, 603, 604, 605, 606, 607, 608, 609, 610, 611, 612, 613, 614, 615, 616, 617, 618, 619, 620, 621, 622, 623, 624, 625, 626, 627, 628, 629, 630, 631, 632, 633, 634, 635, 636, 637, 638, 639, 640, 641, 642, 643, 644, 645, 646, 647, 648, 649, 650, 651, 652, 653, 654, 655, 656, 657, 658, 659, 660, 661, 662, 663, 664, 665, 666, 667, 668, 669, 670, 671, 672, 673, 674, 675, 676, 677, 678, 679, 680, 681, 682, 683, 684, 685, 686, 687, 688, 689, 690, 691, 692, 693, 694, 695, 696, 697, 698, 699, 700, 701, 702, 703, 704, 705, 706, 707, 708, 709, 710, 711, 712, 713, 714, 715, 716, 717, 718, 719, 720, 721, 722, 723, 724, 725, 726, 727, 728, 729, 730, 731, 732, 733, 734, 735, 736, 737, 738, 739, 740, 741, 742, 743, 744, 745, 746, 747, 748, 749, 750, 751, 752, 753, 754, 755, 756, 757, 758, 759, 760, 761, 762, 763, 764, 765, 766, 767, 768, 769, 770, 771, 772, 773, 774, 775, 776, 777, 778, 779, 780, 781, 782, 783, 784, 785, 786, 787, 788, 789, 790, 791, 792, 793, 794, 795, 796, 797, 798, 799, 800, 801, 802, 803, 804, 805, 806, 807, 808, 809, 810, 811, 812, 813, 814, 815, 816, 817, 818, 819, 820, 821, 822, 823, 824, 825, 826, 827, 828, 829, 830, 831, 832, 833, 834, 835, 836, 837, 838, 839, 840, 841, 842, 843, 844, 845, 846, 847, 848, 849, 850, 851, 852, 853, 854, 855, 856, 857, 858, 859, 860, 861, 862, 863, 864, 865, 866, 867, 868, 869, 870, 871, 872, 873, 874, 875, 876, 877, 878, 879, 880, 881, 882, 883, 884, 885, 886, 887, 888, 889, 890, 891, 892, 893, 894, 895, 896, 897, 898, 899, 900, 901, 902, 903, 904, 905, 906, 907, 908, 909, 910, 911, 912, 913, 914, 915, 916, 917, 918, 919, 920, 921, 922, 923, 924, 925, 926, 927, 928, 929, 930, 931, 932, 933, 934, 935, 936, 937, 938, 939, 940, 941, 942, 943, 944, 945, 946, 947, 948, 949, 950, 951, 952, 953, 954, 955, 956, 957, 958, 959, 960, 961, 962, 963, 964, 965, 966, 967, 968, 969, 970, 971, 972, 973, 974, 975, 976, 977, 978, 979, 980, 981, 982, 983, 984, 985, 986, 987, 988, 989, 990, 991, 992, 993, 994, 995, 996, 997, 998, 999, 1000, 1001, 1002, 1003, 1004, 1005, 1006, 1007, 1008, 1009, 1010, 1011, 1012, 1013, 1014, 1015, 1016, 1017, 1018, 1019, 1020, 1021, 1022, 1023, 1024, 1025, 1026, 1027, 1028, 1029, 1030, 1031, 1032, 1033, 1034, 1035, 1036, 1037, 1038, 1039, 1040, 1041, 1042, 1043, 1044, 1045, 1046, 1047, 1048, 1049, 1050, 1051, 1052, 1053, 1054, 1055, 1056, 1057, 1058, 1059, 1060, 1061, 1062, 1063, 1064, 1065, 1066, 1067, 1068, 1069, 1070, 1071, 1072, 1073, 1074, 1075, 1076, 1077, 1078, 1079, 1080, 1081, 1082, 1083, 1084, 1085, 1086, 1087, 1088, 1089, 1090, 1091, 1092, 1093, 1094, 1095, 1096, 1097, 1098, 1099, 1100, 1101, 1102, 1103, 1104, 1105, 1106, 1107, 1108, 1109, 1110, 1111, 1112, 1113, 1114, 1115, 1116, 1117, 1118, 1119, 1120, 1121, 1122, 1123, 1124, 1125, 1126, 1127, 1128, 1129, 1130, 1131, 1132, 1133, 1134, 1135, 1136, 1137, 1138, 1139, 1140, 1141, 1142, 1143, 1144, 1145, 1146, 1147, 1148, 1149, 1150, 1151, 1152, 1153, 1154, 1155, 1156, 1157, 1158, 1159, 1160, 1161, 1162, 1163, 1164, 1165, 1166, 1167, 1168, 1169, 1170, 1171, 1172, 1173, 1174, 1175, 1176, 1177, 1178, 1179, 1180, 1181, 1182, 1183, 1184, 1185, 1186, 1187, 1188, 1189, 1190, 1191, 1192, 1193, 1194, 1195, 1196, 1197, 1198, 1199, 1200, 1201, 1202, 1203, 1204, 1205, 1206, 1207, 1208, 1209, 1210, 1211, 1212, 1213, 1214, 1215, 1216, 1217, 1218, 1219, 1220, 1221, 1222, 1223, 1224, 1225, 1226, 1227, 1228, 1229, 1230, 1231, 1232, 1233, 1234, 1235, 1236, 1237, 1238, 1239, 1240, 1241, 1242, 1243, 1244, 1245, 1246, 1247, 1248, 1249, 1250, 1251, 1252, 1253, 1254, 1255, 1256, 1257, 1258, 1259, 1260, 1261, 1262, 1263, 1264, 1265, 1266, 1267, 1268, 1269, 1270, 1271, 1272, 1273, 1274, 1275, 1276, 1277, 1278, 1279, 1280, 1281, 1282, 1283, 1284, 1285, 1286, 1287, 1288, 1289, 1290, 1291, 1292, 1293, 1294, 1295, 1296, 1297, 1298, 1299, 1300, 1301, 1302, 1303, 1304, 1305, 1306, 1307, 1308, 1309, 1310, 1311, 1312, 1313, 1314, 1315, 1316, 1317, 1318, 1319, 1320, 1321, 1322, 1323, 1324, 1325, 1326, 1327, 1328, 1329, 1330, 1331, 1332, 1333, 1334, 1335, 1336, 1337, 1338, 1339, 1340, 1341, 1342, 1343, 1344, 1345, 1346, 1347, 1348, 1349, 1350, 1351, 1352, 1353, 1354, 1355, 1356, 1357, 1358, 1359, 1360, 1361, 1362, 1363, 1364, 1365, 1366, 1367, 1368, 1369, 1370, 1371, 1372, 1373, 1374, 1375, 1376, 1377, 1378, 1379, 1380, 1381, 1382, 1383, 1384, 1385, 1386, 1387, 1388, 1389, 1390, 1391, 1392, 1393, 1394, 1395, 1396, 1397, 1398, 1399, 1400, 1401, 1402, 1403, 1404, 1405, 1406, 1407, 1408, 1409, 1410, 1411, 1412, 1413, 1414, 1415, 1416, 1417, 1418, 1419, 1420, 1421, 1422, 1423, 1424, 1425, 1426, 1427, 1428, 1429, 1430, 1431, 1432, 1433, 1434, 1435, 1436, 1437, 1438, 1439, 1440, 1441, 1442, 1443, 1444, 1445, 1446, 1447, 1448, 1449, 1450, 1451, 1452, 1453, 1454, 1455, 1456, 1457, 1458, 1459, 1460, 1461, 1462, 1463, 1464, 1465, 1466, 1467, 1468, 1469, 1470, 1471, 1472, 1473, 1474, 1475, 1476, 1477, 1478, 1479, 1480, 1481, 1482, 1483, 1484, 1485, 1486, 1487, 1488, 1489, 1490, 1491, 1492, 1493, 1494, 1495, 1496, 1497, 1498, 1499, 1500, 1501, 1502, 1503, 1504, 1505, 1506, 1507, 1508, 1509, 1510, 1511, 1512, 1513, 1514, 1515, 1516, 1517, 1518, 1519, 1520, 1521, 1522, 1523, 1524, 1525, 1526, 1527, 1528, 1529, 1530, 1531, 1532, 1533, 1534, 1535, 1536, 1537, 1538, 1539, 1540, 1541, 1542, 1543, 1544, 1545, 1546, 1547, 1548, 1549, 1550, 1551, 1552, 1553, 1554, 1555, 1556, 1557, 1558, 1559, 1560, 1561, 1562, 1563, 1564, 1565, 1566, 1567, 1568, 1569, 1570, 1571, 1572, 1573, 1574, 1575, 1576, 1577, 1578, 1579, 1580, 1581, 1582, 1583, 1584, 1585, 1586, 1587, 1588, 1589, 1590, 1591, 1592, 1593, 1594, 1595, 1596, 1597, 1598, 1599, 1600, 1601, 1602, 1603, 1604, 1605, 1606, 1607, 1608, 1609, 1610, 1611, 1612, 1613, 1614, 1615, 1616, 1617, 1618, 1619, 1620, 1621, 1622, 1623, 1624, 1625, 1626, 1627, 1628, 1629, 1630, 1631, 1632, 1633, 1634, 1635, 1636, 1637, 1638, 1639, 1640, 1641, 1642, 1643, 1644, 1645, 1646, 1647, 1648, 1649, 1650, 1651, 1652, 1653, 1654, 1655, 1656, 1657, 1658, 1659, 1660, 1661, 1662, 1663, 1664, 1665, 1666, 1667, 1668, 1669, 1670, 1671, 1672, 1673, 1674, 1675, 1676, 1677, 1678, 1679, 1680, 1681, 1682, 1683, 1684, 1685, 1686, 1687, 1688, 1689, 1690, 1691, 1692, 1693, 1694, 1695, 1696, 1697, 1698, 1699, 1700, 1701, 1702, 1703, 1704, 1705, 1706, 1707, 1708, 1709, 1710, 1711, 1712, 1713, 1714, 1715, 1716, 1717, 1718, 1719, 1720, 1721, 1722, 1723, 1724, 1725, 1726, 1727, 1728, 1729, 1730, 1731, 1732, 1733, 1734, 1735, 1736, 1737, 1738, 1739, 1740, 1741, 1742, 1743, 1744, 1745, 1746, 1747, 1748, 1749, 1750, 1751, 1752, 1753, 1754, 1755, 1756, 1757, 1758, 1759, 1760, 1761, 1762, 1763, 1764, 1765, 1766, 1767, 1768, 1769, 1770, 1771, 1772, 1773, 1774, 1775, 1776, 1777, 1778, 1779, 1780, 1781, 1782, 1783, 1784, 1785, 1786, 1787, 1788, 1789, 1790, 1791, 1792, 1793, 1794, 1795, 1796, 1797, 1798, 1799, 1800, 1801, 1802, 1803, 1804, 1805, 1806, 1807, 1808, 1809, 1810, 1811, 1812, 1813, 1814, 1815, 1816, 1817, 1818, 1819, 1820, 1821, 1822, 1823, 1824, 1825, 1826, 1827, 1828, 1829, 1830, 1831, 1832, 1833, 1834, 1835, 1836, 1837, 1838, 1839, 1840, 1841, 1842, 1843, 1844, 1845, 1846, 1847, 1848, 1849, 1850, 1851, 1852, 1853, 1854, 1855, 1856, 1857, 1858, 1859, 1860, 1861, 1862, 1863, 1864, 1865, 1866, 1867, 1868, 1869, 1870, 1871, 1872, 1873, 1874, 1875, 1876, 1877, 1878, 1879, 1880, 1881, 1882, 1883, 1884, 1885, 1886, 1887, 1888, 1889, 1890, 1891, 1892, 1893, 1894, 1895, 1896, 1897, 1898, 1899, 1900, 1901, 1902, 1903, 1904, 1905, 1906, 1907, 1908, 1909, 1910, 1911, 1912, 1913, 1914, 1915, 1916, 1917, 1918, 1919, 1920, 1921, 1922, 1923, 1924, 1925, 1926, 1927, 1928, 1929, 1930, 1931, 1932, 1933, 1934, 1935, 1936, 1937, 1938, 1939, 1940, 1941, 1942, 1943, 1944, 1945, 1946, 1947, 1948, 1949, 1950, 1951, 1952, 1953, 1954, 1955, 1956, 1957, 1958, 1959, 1960, 1961, 1962, 1963, 1964, 1965, 1966, 1967, 1968, 1969, 1970, 1971, 1972, 1973, 1974, 1975, 1976, 1977, 1978, 1979, 1980, 1981, 1982, 1983, 1984, 1985, 1986, 1987, 1988, 1989, 1990, 1991, 1992, 1993, 1994, 1995, 1996, 1997, 1998, 1999, 2000, 2001, 2002, 2003, 2004, 2005, 2006, 2007, 2008, 2009, 2010, 2011, 2012, 2013, 2014, 2015, 2016, 2017, 2018, 2019, 2020, 2021, 2022, 2023, 2024, 2025, 2026, 2027, 2028, 2029, 2030, 2031, 2032, 2033, 2034, 2035, 2036, 2037, 2038, 2039, 2040, 2041, 2042, 2043, 2044, 2045, 2046, 2047, 2048, 2049, 2050, 2051, 2052, 2053, 2054, 2055, 2056, 2057, 2058, 2059, 2060, 2061, 2062, 2063, 2064, 2065, 2066, 2067, 2068, 2069, 2070, 2071, 2072, 2073, 2074, 2075, 2076, 2077, 2078, 2079, 2080, 2081, 2082, 2083, 2084, 2085, 2086, 2087, 2088, 2089, 2090, 2091, 2092, 2093, 2094, 2095, 2096, 2097, 2098, 2099, 2100, 2101, 2102, 2103, 2104, 2105, 2106, 2107, 2108, 2109, 2110, 2111, 2112, 2113, 2114, 2115, 2116, 2117, 2118, 2119, 2120, 2121, 2122, 2123, 2124, 2125, 2126, 2127, 2128, 2129, 2130, 2131, 2132, 2133, 2134, 2135, 2136, 2137, 2138, 2139, 2140, 2141, 2142, 2143, 2144, 2145, 2146, 2147, 2148, 2149, 2150, 2151, 2152, 2153, 2154, 2155, 2156, 2157, 2158, 2159, 2160, 2161, 2162, 2163, 2164, 2165, 2166, 2167, 2168, 2169, 2170, 2171, 2172, 2173, 2174, 2175, 2176, 2177, 2178, 2179, 2180, 2181, 2182, 2183, 2184, 2185, 2186, 2187, 2188, 2189, 2190, 2191, 2192, 2193, 2194, 2195, 2196, 2197, 2198, 2199, 2200, 2201, 2202, 2203, 2204, 2205, 2206, 2207, 2208, 2209, 2210, 2211, 2212, 2213, 2214, 2215, 2216, 2217, 2218, 2219, 2220, 2221, 2222, 2223, 2224, 2225, 2226, 2227, 2228, 2229, 2230, 2231, 2232, 2233, 2234, 2235, 2236, 2237, 2238, 2239, 2240, 2241, 2242, 2243, 2244, 2245, 2246, 2247, 2248, 2249, 2250, 2251, 2252, 2253, 2254, 2255, 2256, 2257, 2258, 2259, 2260, 2261, 2262, 2263, 2264, 2265, 2266, 2267, 2268, 2269, 2270, 2271, 2272, 2273, 2274, 2275, 2276, 2277, 2278, 2279, 2280, 2281, 2282, 2283, 2284, 2285, 2286, 2287, 2288, 2289, 2290, 2291, 2292, 2293, 2294, 2295, 2296, 2297, 2298, 2299, 2300, 2301, 2302, 2303, 2304, 2305, 2306, 2307, 2308, 2309, 2310, 2311, 2312, 2313, 2314, 2315, 2316, 2317, 2318, 2319, 2320, 2321, 2322, 2323, 2324, 2325, 2326, 2327, 2328, 2329, 2330, 2331, 2332, 2333, 2334, 2335, 2336, 2337, 2338, 2339, 2340, 2341, 2342, 2343, 2344, 2345, 2346, 2347, 2348, 2349, 2350, 2351, 2352, 2353, 2354, 2355, 2356, 2357, 2358, 2359, 2360, 2361, 2362, 2363, 2364, 2365, 2366, 2367, 2368, 2369, 2370, 2371, 2372, 2373, 2374, 2375, 2376, 2377, 2378, 2379, 2380, 2381, 2382, 2383, 2384, 2385, 2386, 2387, 2388, 2389, 2390, 2391, 2392, 2393, 2394, 2395, 2396, 2397, 2398, 2399, 2400, 2401, 2402, 2403, 2404, 2405, 2406, 2407, 2408, 2409, 2410, 2411, 2412, 2413, 2414, 2415, 2416, 2417, 2418, 2419, 2420, 2421, 2422, 2423, 2424, 2425, 2426, 2427, 2428, 2429, 2430, 2431, 2432, 2433, 2434, 2435, 2436, 2437, 2438, 2439, 2440, 2441, 2442, 2443, 2444, 2445, 2446, 2447, 2448, 2449, 2450, 2451, 2452, 2453, 2454, 2455, 2456, 2457, 2458, 2459, 2460, 2461, 2462, 2463, 2464, 2465, 2466, 2467, 2468, 2469, 2470, 2471, 2472, 2473, 2474, 2475, 2476, 2477, 2478, 2479, 2480, 2481, 2482, 2483, 2484, 2485, 2486, 2487, 2488, 2489, 2490, 2491, 2492, 2493, 2494, 2495, 2496, 2497, 2498, 2499, 2500, 2501, 2502, 2503, 2504, 2505, 2506, 2507, 2508, 2509, 2510, 2511, 2512, 2513, 2514, 2515, 2516, 2517, 2518, 2519, 2520, 2521, 2522, 2523, 2524, 2525, 2526, 2527, 2528, 2529, 2530, 2531, 2532, 2533, 2534, 2535, 2536, 2537, 2538, 2539, 2540, 2541, 2542, 2543, 2544, 2545, 2546, 2547, 2548, 2549, 2550, 2551, 2552, 2553, 2554, 2555, 2556, 2557, 2558, 2559, 2560, 2561, 2562, 2563, 2564, 2565, 2566, 2567, 2568, 2569, 2570, 2571, 2572, 2573, 2574, 2575, 2576, 2577, 2578, 2579, 2580, 2581, 2582, 2583, 2584, 2585, 2586, 2587, 2588, 2589, 2590, 2591, 2592, 2593, 2594, 2595, 2596, 2597, 2598, 2599, 2600, 2601, 2602, 2603, 2604, 2605, 2606, 2607, 2608, 2609, 2610, 2611, 2612, 2613, 2614, 2615, 2616, 2617, 2618, 2619, 2620, 2621, 2622, 2623, 2624, 2625, 2626, 2627, 2628, 2629, 2630, 2631, 2632, 2633, 2634, 2635, 2636, 2637, 2638, 2639, 2640, 2641, 2642, 2643, 2644, 2645, 2646, 2647, 2648, 2649, 2650, 2651, 2652, 2653, 2654, 2655, 2656, 2657, 2658, 2659, 2660, 2661, 2662, 2663, 2664, 2665, 2666, 2667, 2668, 2669, 2670, 2671, 2672, 2673, 2674, 2675, 2676, 2677, 2678, 2679, 2680, 2681, 2682, 2683, 2684, 2685, 2686, 2687, 2688, 2689, 2690, 2691, 2692, 2693, 2694, 2695, 2696, 2697, 2698, 2699, 2700, 2701, 2702, 2703, 2704, 2705, 2706, 2707, 2708, 2709, 2710, 2711, 2712, 2713, 2714, 2715, 2716, 2717, 2718, 2719, 2720, 2721, 2722, 2723, 2724, 2725, 2726, 2727, 2728, 2729, 2730, 2731, 2732, 2733, 2734, 2735, 2736, 2737, 2738, 2739, 2740, 2741, 2742, 2743, 2744, 2745, 2746, 2747, 2748, 2749, 2750, 2751, 2752, 2753, 2754, 2755, 2756, 2757, 2758, 2759, 2760, 2761, 2762, 2763, 2764, 2765, 2766, 2767, 2768, 2769, 2770, 2771, 2772, 2773, 2774, 2775, 2776, 2777, 2778, 2779, 2780, 2781, 2782, 2783, 2784, 2785, 2786, 2787, 2788, 2789, 2790, 2791, 2792, 2793, 2794, 2795, 2796, 2797, 2798, 2799, 2800, 2801, 2802, 2803, 2804, 2805, 2806, 2807, 2808, 2809, 2810, 2811, 2812, 2813, 2814, 2815, 2816, 2817, 2818, 2819, 2820, 2821, 2822, 2823, 2824, 2825, 2826, 2827, 2828, 2829, 2830, 2831, 2832, 2833, 2834, 2835, 2836, 2837, 2838, 2839, 2840, 2841, 2842, 2843, 2844, 2845, 2846, 2847, 2848, 2849, 2850, 2851, 2852, 2853, 2854, 2855, 2856, 2857, 2858, 2859, 2860, 2861, 2862, 2863, 2864, 2865, 2866, 2867, 2868, 2869, 2870, 2871, 2872, 2873, 2874, 2875, 2876, 2877, 2878, 2879, 2880, 2881, 2882, 2883, 2884, 2885, 2886, 2887, 2888, 2889, 2890, 2891, 2892, 2893, 2894, 2895, 2896, 2897, 2898, 2899, 2900, 2901, 2902, 2903, 2904, 2905, 2906, 2907, 2908, 2909, 2910, 2911, 2912, 2913, 2914, 2915, 2916, 2917, 2918, 2919, 2920, 2921, 2922, 2923, 2924, 2925, 2926, 2927, 2928, 2929, 2930, 2931, 2932, 2933, 2934, 2935, 2936, 2937, 2938, 2939, 2940, 2941, 2942, 2943, 2944, 2945, 2946, 2947, 2948, 2949, 2950, 2951, 2952, 2953, 2954, 2955, 2956, 2957, 2958, 2959, 2960, 2961, 2962, 2963, 2964, 2965, 2966, 2967, 2968, 2969, 2970, 2971, 2972, 2973, 2974, 2975, 2976, 2977, 2978, 2979, 2980, 2981, 2982, 2983, 2984, 2985, 2986, 2987, 2988, 2989, 2990, 2991, 2992, 2993, 2994, 2995, 2996, 2997, 2998, 2999, 3000, 3001, 3002, 3003, 3004, 3005, 3006, 3007, 3008, 3009, 3010, 3011, 3012, 3013, 3014, 3015, 3016, 3017, 3018, 3019, 3020, 3021, 3022, 3023, 3024, 3025, 3026, 3027, 3028, 3029, 3030, 3031, 3032, 3033, 3034, 3035, 3036, 3037, 3038, 3039, 3040, 3041, 3042, 3043, 3044, 3045, 3046, 3047, 3048, 3049, 3050, 3051, 3052, 3053, 3054, 3055, 3056, 3057, 3058, 3059, 3060, 3061, 3062, 3063, 3064, 3065, 3066, 3067, 3068, 3069, 3070, 3071, 3072, 3073, 3074, 3075, 3076, 3077, 3078, 3079, 3080, 3081, 3082, 3083, 3084, 3085, 3086, 3087, 3088, 3089, 3090, 3091, 3092, 3093, 3094, 3095, 3096, 3097, 3098, 3099, 3100, 3101, 3102, 3103, 3104, 3105, 3106, 3107, 3108, 3109, 3110, 3111, 3112, 3113, 3114, 3115, 3116, 3117, 3118, 3119, 3120, 3121, 3122, 3123, 3124, 3125, 3126, 3127, 3128, 3129, 3130, 3131, 3132, 3133, 3134, 3135, 3136, 3137, 3138, 3139, 3140, 3141, 3142, 3143, 3144, 3145, 3146, 3147, 3148, 3149, 3150, 3151, 3152, 3153, 3154, 3155, 3156, 3157, 3158, 3159, 3160, 3161, 3162, 3163, 3164, 3165, 3166, 3167, 3168, 3169, 3170, 3171, 3172, 3173, 3174, 3175, 3176, 3177, 3178, 3179, 3180, 3181, 3182, 3183, 3184, 3185, 3186, 3187, 3188, 3189, 3190, 3191, 3192, 3193, 3194, 3195, 3196, 3197, 3198, 3199, 3200, 3201, 3202, 3203, 3204, 3205, 3206, 3207, 3208, 3209, 3210, 3211, 3212, 3213, 3214, 3215, 3216, 3217, 3218, 3219, 3220, 3221, 3222, 3223, 3224, 3225, 3226, 3227, 3228, 3229, 3230, 3231, 3232, 3233, 3234, 3235, 3236, 3237, 3238, 3239, 3240, 3241, 3242, 3243, 3244, 3245, 3246, 3247, 3248, 3249, 3250, 3251, 3252, 3253, 3254, 3255, 3256, 3257, 3258, 3259, 3260, 3261, 3262, 3263, 3264, 3265, 3266, 3267, 3268, 3269, 3270, 3271, 3272, 3273, 3274, 3275, 3276, 3277, 3278, 3279, 3280, 3281, 3282, 3283, 3284, 3285, 3286, 3287, 3288, 3289, 3290, 3291, 3292, 3293, 3294, 3295, 3296, 3297, 3298, 3299, 3300, 3301, 3302, 3303, 3304, 3305, 3306, 3307, 3308, 3309, 3310, 3311, 3312, 3313, 3314, 3315, 3316, 3317, 3318, 3319, 3320, 3321, 3322, 3323, 3324, 3325, 3326, 3327, 3328, 3329, 3330, 3331, 3332, 3333, 3334, 3335, 3336, 3337, 3338, 3339, 3340, 3341, 3342, 3343, 3344, 3345, 3346, 3347, 3348, 3349, 3350, 3351, 3352, 3353, 3354, 3355, 3356, 3357, 3358, 3359, 3360, 3361, 3362, 3363, 3364, 3365, 3366, 3367, 3368, 3369, 3370, 3371, 3372, 3373, 3374, 3375, 3376, 3377, 3378, 3379, 3380, 3381, 3382, 3383, 3384, 3385, 3386, 3387, 3388, 3389, 3390, 3391, 3392, 3393, 3394, 3395, 3396, 3397, 3398, 3399, 3400, 3401, 3402, 3403, 3404, 3405, 3406, 3407, 3408, 3409, 3410, 3411, 3412, 3413, 3414, 3415, 3416, 3417, 3418, 3419, 3420, 3421, 3422, 3423, 3424, 3425, 3426, 3427, 3428, 3429, 3430, 3431, 3432, 3433, 3434, 3435, 3436, 3437, 3438, 3439, 3440, 3441, 3442, 3443, 3444, 3445, 3446, 3447, 3448, 3449, 3450, 3451, 3452, 3453, 3454, 3455, 3456, 3457, 3458, 3459, 3460, 3461, 3462, 3463, 3464, 3465, 3466, 3467, 3468, 3469, 3470, 3471, 3472, 3473, 3474, 3475, 3476, 3477, 3478, 3479, 3480, 3481, 3482, 3483, 3484, 3485, 3486, 3487, 3488, 3489, 3490, 3491, 3492, 3493, 3494, 3495, 3496, 3497, 3498, 3499, 3500, 3501, 3502, 3503, 3504, 3505, 3506, 3507, 3508, 3509, 3510, 3511, 3512, 3513, 3514, 3515, 3516, 3517, 3518, 3519, 3520, 3521, 3522, 3523, 3524, 3525, 3526, 3527, 3528, 3529, 3530, 3531, 3532, 3533, 3534, 3535, 3536, 3537, 3538, 3539, 3540, 3541, 3542, 3543, 3544, 3545, 3546, 3547, 3548, 3549, 3550, 3551, 3552, 3553, 3554, 3555, 3556, 3557, 3558, 3559, 3560, 3561, 3562, 3563, 3564, 3565, 3566, 3567, 3568, 3569, 3570, 3571, 3572, 3573, 3574, 3575, 3576, 3577, 3578, 3579, 3580, 3581, 3582, 3583, 3584, 3585, 3586, 3587, 3588, 3589, 3590, 3591, 3592, 3593, 3594, 3595, 3596, 3597, 3598, 3599, 3600, 3601, 3602, 3603, 3604, 3605, 3606, 3607, 3608, 3609, 3610, 3611, 3612, 3613, 3614, 3615, 3616, 3617, 3618, 3619, 3620, 3621, 3622, 3623, 3624, 3625, 3626, 3627, 3628, 3629, 3630, 3631, 3632, 3633, 3634, 3635, 3636, 3637, 3638, 3639, 3640, 3641, 3642, 3643, 3644, 3645, 3646, 3647, 3648, 3649, 3650, 3651, 3652, 3653, 3654, 3655, 3656, 3657, 3658, 3659, 3660, 3661, 3662, 3663, 3664, 3665, 3666, 3667, 3668, 3669, 3670, 3671, 3672, 3673, 3674, 3675, 3676, 3677, 3678, 3679, 3680, 3681, 3682, 3683, 3684, 3685, 3686, 3687, 3688, 3689, 3690, 3691, 3692, 3693, 3694, 3695, 3696, 3697, 3698, 3699, 3700, 3701, 3702, 3703, 3704, 3705, 3706, 3707, 3708, 3709, 3710, 3711, 3712, 3713, 3714, 3715, 3716, 3717, 3718, 3719, 3720, 3721, 3722, 3723, 3724, 3725, 3726, 3727, 3728, 3729, 3730, 3731, 3732, 3733, 3734, 3735, 3736, 3737, 3738, 3739, 3740, 3741, 3742, 3743, 3744, 3745, 3746, 3747, 3748, 3749, 3750, 3751, 3752, 3753, 3754, 3755, 3756, 3757, 3758, 3759, 3760, 3761, 3762, 3763, 3764, 3765, 3766, 3767, 3768, 3769, 3770, 3771, 3772, 3773, 3774, 3775, 3776, 3777, 3778, 3779, 3780, 3781, 3782, 3783, 3784, 3785, 3786, 3787, 3788, 3789, 3790, 3791, 3792, 3793, 3794, 3795, 3796, 3797, 3798, 3799, 3800, 3801, 3802, 3803, 3804, 3805, 3806, 3807, 3808, 3809, 3810, 3811, 3812, 3813, 3814, 3815, 3816, 3817, 3818, 3819, 3820, 3821, 3822, 3823, 3824, 3825, 3826, 3827, 3828, 3829, 3830, 3831, 3832, 3833, 3834, 3835, 3836, 3837, 3838, 3839, 3840, 3841, 3842, 3843, 3844, 3845, 3846, 3847, 3848, 3849, 3850, 3851, 3852, 3853, 3854, 3855, 3856, 3857, 3858, 3859, 3860, 3861, 3862, 3863, 3864, 3865, 3866, 3867, 3868, 3869, 3870, 3871, 3872, 3873, 3874, 3875, 3876, 3877, 3878, 3879, 3880, 3881, 3882, 3883, 3884, 3885, 3886, 3887, 3888, 3889, 3890, 3891, 3892, 3893, 3894, 3895, 3896, 3897, 3898, 3899, 3900, 3901, 3902, 3903, 3904, 3905, 3906, 3907, 3908, 3909, 3910, 3911, 3912, 3913, 3914, 3915, 3916, 3917, 3918, 3919, 3920, 3921, 3922, 3923, 3924, 3925, 3926, 3927, 3928, 3929, 3930, 3931, 3932, 3933, 3934, 3935, 3936, 3937, 3938, 3939, 3940, 3941, 3942, 3943, 3944, 3945, 3946, 3947, 3948, 3949, 3950, 3951, 3952, 3953, 3954, 3955, 3956, 3957, 3958, 3959, 3960, 3961, 3962, 3963, 3964, 3965, 3966, 3967, 3968, 3969, 3970, 3971, 3972, 3973, 3974, 3975, 3976, 3977, 3978, 3979, 3980, 3981, 3982, 3983, 3984, 3985, 3986, 3987, 3988, 3989, 3990, 3991, 3992, 3993, 3994, 3995, 3996, 3997, 3998, 3999, 4000, 4001, 4002, 4003, 4004, 4005, 4006, 4007, 4008, 4009, 4010, 4011, 4012, 4013, 4014, 4015, 4016, 4017, 4018, 4019, 4020, 4021, 4022, 4023, 4024, 4025, 4026, 4027, 4028, 4029, 4030, 4031, 4032, 4033, 4034, 4035, 4036, 4037, 4038, 4039, 4040, 4041, 4042, 4043, 4044, 4045, 4046, 4047, 4048, 4049, 4050, 4051, 4052, 4053, 4054, 4055, 4056, 4057, 4058, 4059, 4060, 4061, 4062, 4063, 4064, 4065, 4066, 4067, 4068, 4069, 4070, 4071, 4072, 4073, 4074, 4075, 4076, 4077, 4078, 4079, 4080, 4081, 4082, 4083, 4084, 4085, 4086, 4087, 4088, 4089, 4090, 4091, 4092, 4093, 4094, 4095 ]; + gamma = 100; + contrast = 100; + black_level = 0; + white_level = 255; +}; +isp_shape : +{ + noise_reduce = false; + vflip = false; + hflip = false; + rotate_dir = 0; + sharpness = 0; + defect_corr = true; + flat_fielding_corr_enable = false; + flat_fielding_corr_param_file_path = ""; + denoise3d_enable = false; + denoise3d_length = 0; + denoise3d_use_weight = false; +}; +trigger_set : +{ + count_per_trigger = 1; + enable_trigger = false; + trigger_sel = 0; + ext_trig_delay_time = 0; + ext_trig_signal_type = 0; + ext_trig_shutter_type = 0; + strobe_pulse_width = 10; + strobe_delay_time = 50; + strobe_polarity = 0; + strobe_mode = 1; + jitter_time = 50000; +}; +wdr : +{ + awdr_enable = false; +}; diff --git a/others/energy.Config b/others/energy.Config new file mode 100644 index 0000000..327ec1d --- /dev/null +++ b/others/energy.Config @@ -0,0 +1,153 @@ +create_time = "2019-05-14 19:59:50"; +internal_id = "E7FCFFE8999B"; +resolution : +{ + image_size : + { + iIndex = 1; + acDescription = "640X480 ROI"; + uBinSumMode = 0; + uBinAverageMode = 0; + uSkipMode = 0; + uResampleMask = 0; + iHOffsetFOV = 56; + iVOffsetFOV = 0; + iWidthFOV = 640; + iHeightFOV = 480; + iWidth = 640; + iHeight = 480; + iWidthZoomHd = 0; + iHeightZoomHd = 0; + iWidthZoomSw = 0; + iHeightZoomSw = 0; + }; + image_size_for_snap : + { + iIndex = 255; + acDescription = ""; + uBinSumMode = 0; + uBinAverageMode = 0; + uSkipMode = 0; + uResampleMask = 0; + iHOffsetFOV = 0; + iVOffsetFOV = 0; + iWidthFOV = 0; + iHeightFOV = 0; + iWidth = 0; + iHeight = 0; + iWidthZoomHd = 0; + iHeightZoomHd = 0; + iWidthZoomSw = 0; + iHeightZoomSw = 0; + }; + transfer_roi_mask = 0; + transfer_roi_x1 = [ 0, 0, 0, 0 ]; + transfer_roi_y1 = [ 0, 0, 0, 0 ]; + transfer_roi_x2 = [ 0, 0, 0, 0 ]; + transfer_roi_y2 = [ 0, 0, 0, 0 ]; +}; +exposure : +{ + anti_flick_freq = 0; + anti_flick = false; + show_ae_window = false; + ae_window_height = 0; + ae_window_width = 0; + ae_window_voff = 0; + ae_window_hoff = 0; + analog_gain = 64; + exp_time = 10000.0; + ae_target = 120; + ae_enable = false; + user_exposure_time = 10000.0; + user_ae_min_exposure_time = 0.0; + user_ae_max_exposure_time = 10000000.0; + user_ae_min_analog_gain = 16; + user_ae_max_analog_gain = 64; + ae_threshold = 10; +}; +video_format : +{ + frame_speed_sel = 1; + trans_pack_len_sel = 0; + media_type_sel = 0; + auto_reconnect = true; + hdr_gain_mode = 0; +}; +overlay : +{ + cross_line : + { + show = [ false, false, false, false, false, false, false, false, false ]; + color = [ 6458569, 15539236, 16756425, 13156327, 16773632, 0, 0, 0, 0 ]; + pos = [ 376, 240, 188, 120, 564, 120, 188, 360, 564, 360, 0, 0, 0, 0, 0, 0, 0, 0 ]; + }; +}; +isp_color : +{ + auto_wb = false; + mono = false; + inverse = false; + r_gain = 100; + g_gain = 100; + b_gain = 100; + wb_window_hoff = 0; + wb_window_voff = 0; + wb_window_width = 0; + wb_window_height = 0; + show_wb_window = false; + saturation = 100; + clr_temp_mode = 0; + clr_temp_sel = 2; + user_clr_temp : + { + desc = ""; + matrix = [ 1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0 ]; + r = 1.0; + g = 1.0; + b = 1.0; + }; + raw2rgb_algorithm_sw_sel = 1; +}; +isp_lut : +{ + lut_preset_sel = 0; + lut_mode = 0; + user_def_lut = [ 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 256, 257, 258, 259, 260, 261, 262, 263, 264, 265, 266, 267, 268, 269, 270, 271, 272, 273, 274, 275, 276, 277, 278, 279, 280, 281, 282, 283, 284, 285, 286, 287, 288, 289, 290, 291, 292, 293, 294, 295, 296, 297, 298, 299, 300, 301, 302, 303, 304, 305, 306, 307, 308, 309, 310, 311, 312, 313, 314, 315, 316, 317, 318, 319, 320, 321, 322, 323, 324, 325, 326, 327, 328, 329, 330, 331, 332, 333, 334, 335, 336, 337, 338, 339, 340, 341, 342, 343, 344, 345, 346, 347, 348, 349, 350, 351, 352, 353, 354, 355, 356, 357, 358, 359, 360, 361, 362, 363, 364, 365, 366, 367, 368, 369, 370, 371, 372, 373, 374, 375, 376, 377, 378, 379, 380, 381, 382, 383, 384, 385, 386, 387, 388, 389, 390, 391, 392, 393, 394, 395, 396, 397, 398, 399, 400, 401, 402, 403, 404, 405, 406, 407, 408, 409, 410, 411, 412, 413, 414, 415, 416, 417, 418, 419, 420, 421, 422, 423, 424, 425, 426, 427, 428, 429, 430, 431, 432, 433, 434, 435, 436, 437, 438, 439, 440, 441, 442, 443, 444, 445, 446, 447, 448, 449, 450, 451, 452, 453, 454, 455, 456, 457, 458, 459, 460, 461, 462, 463, 464, 465, 466, 467, 468, 469, 470, 471, 472, 473, 474, 475, 476, 477, 478, 479, 480, 481, 482, 483, 484, 485, 486, 487, 488, 489, 490, 491, 492, 493, 494, 495, 496, 497, 498, 499, 500, 501, 502, 503, 504, 505, 506, 507, 508, 509, 510, 511, 512, 513, 514, 515, 516, 517, 518, 519, 520, 521, 522, 523, 524, 525, 526, 527, 528, 529, 530, 531, 532, 533, 534, 535, 536, 537, 538, 539, 540, 541, 542, 543, 544, 545, 546, 547, 548, 549, 550, 551, 552, 553, 554, 555, 556, 557, 558, 559, 560, 561, 562, 563, 564, 565, 566, 567, 568, 569, 570, 571, 572, 573, 574, 575, 576, 577, 578, 579, 580, 581, 582, 583, 584, 585, 586, 587, 588, 589, 590, 591, 592, 593, 594, 595, 596, 597, 598, 599, 600, 601, 602, 603, 604, 605, 606, 607, 608, 609, 610, 611, 612, 613, 614, 615, 616, 617, 618, 619, 620, 621, 622, 623, 624, 625, 626, 627, 628, 629, 630, 631, 632, 633, 634, 635, 636, 637, 638, 639, 640, 641, 642, 643, 644, 645, 646, 647, 648, 649, 650, 651, 652, 653, 654, 655, 656, 657, 658, 659, 660, 661, 662, 663, 664, 665, 666, 667, 668, 669, 670, 671, 672, 673, 674, 675, 676, 677, 678, 679, 680, 681, 682, 683, 684, 685, 686, 687, 688, 689, 690, 691, 692, 693, 694, 695, 696, 697, 698, 699, 700, 701, 702, 703, 704, 705, 706, 707, 708, 709, 710, 711, 712, 713, 714, 715, 716, 717, 718, 719, 720, 721, 722, 723, 724, 725, 726, 727, 728, 729, 730, 731, 732, 733, 734, 735, 736, 737, 738, 739, 740, 741, 742, 743, 744, 745, 746, 747, 748, 749, 750, 751, 752, 753, 754, 755, 756, 757, 758, 759, 760, 761, 762, 763, 764, 765, 766, 767, 768, 769, 770, 771, 772, 773, 774, 775, 776, 777, 778, 779, 780, 781, 782, 783, 784, 785, 786, 787, 788, 789, 790, 791, 792, 793, 794, 795, 796, 797, 798, 799, 800, 801, 802, 803, 804, 805, 806, 807, 808, 809, 810, 811, 812, 813, 814, 815, 816, 817, 818, 819, 820, 821, 822, 823, 824, 825, 826, 827, 828, 829, 830, 831, 832, 833, 834, 835, 836, 837, 838, 839, 840, 841, 842, 843, 844, 845, 846, 847, 848, 849, 850, 851, 852, 853, 854, 855, 856, 857, 858, 859, 860, 861, 862, 863, 864, 865, 866, 867, 868, 869, 870, 871, 872, 873, 874, 875, 876, 877, 878, 879, 880, 881, 882, 883, 884, 885, 886, 887, 888, 889, 890, 891, 892, 893, 894, 895, 896, 897, 898, 899, 900, 901, 902, 903, 904, 905, 906, 907, 908, 909, 910, 911, 912, 913, 914, 915, 916, 917, 918, 919, 920, 921, 922, 923, 924, 925, 926, 927, 928, 929, 930, 931, 932, 933, 934, 935, 936, 937, 938, 939, 940, 941, 942, 943, 944, 945, 946, 947, 948, 949, 950, 951, 952, 953, 954, 955, 956, 957, 958, 959, 960, 961, 962, 963, 964, 965, 966, 967, 968, 969, 970, 971, 972, 973, 974, 975, 976, 977, 978, 979, 980, 981, 982, 983, 984, 985, 986, 987, 988, 989, 990, 991, 992, 993, 994, 995, 996, 997, 998, 999, 1000, 1001, 1002, 1003, 1004, 1005, 1006, 1007, 1008, 1009, 1010, 1011, 1012, 1013, 1014, 1015, 1016, 1017, 1018, 1019, 1020, 1021, 1022, 1023, 1024, 1025, 1026, 1027, 1028, 1029, 1030, 1031, 1032, 1033, 1034, 1035, 1036, 1037, 1038, 1039, 1040, 1041, 1042, 1043, 1044, 1045, 1046, 1047, 1048, 1049, 1050, 1051, 1052, 1053, 1054, 1055, 1056, 1057, 1058, 1059, 1060, 1061, 1062, 1063, 1064, 1065, 1066, 1067, 1068, 1069, 1070, 1071, 1072, 1073, 1074, 1075, 1076, 1077, 1078, 1079, 1080, 1081, 1082, 1083, 1084, 1085, 1086, 1087, 1088, 1089, 1090, 1091, 1092, 1093, 1094, 1095, 1096, 1097, 1098, 1099, 1100, 1101, 1102, 1103, 1104, 1105, 1106, 1107, 1108, 1109, 1110, 1111, 1112, 1113, 1114, 1115, 1116, 1117, 1118, 1119, 1120, 1121, 1122, 1123, 1124, 1125, 1126, 1127, 1128, 1129, 1130, 1131, 1132, 1133, 1134, 1135, 1136, 1137, 1138, 1139, 1140, 1141, 1142, 1143, 1144, 1145, 1146, 1147, 1148, 1149, 1150, 1151, 1152, 1153, 1154, 1155, 1156, 1157, 1158, 1159, 1160, 1161, 1162, 1163, 1164, 1165, 1166, 1167, 1168, 1169, 1170, 1171, 1172, 1173, 1174, 1175, 1176, 1177, 1178, 1179, 1180, 1181, 1182, 1183, 1184, 1185, 1186, 1187, 1188, 1189, 1190, 1191, 1192, 1193, 1194, 1195, 1196, 1197, 1198, 1199, 1200, 1201, 1202, 1203, 1204, 1205, 1206, 1207, 1208, 1209, 1210, 1211, 1212, 1213, 1214, 1215, 1216, 1217, 1218, 1219, 1220, 1221, 1222, 1223, 1224, 1225, 1226, 1227, 1228, 1229, 1230, 1231, 1232, 1233, 1234, 1235, 1236, 1237, 1238, 1239, 1240, 1241, 1242, 1243, 1244, 1245, 1246, 1247, 1248, 1249, 1250, 1251, 1252, 1253, 1254, 1255, 1256, 1257, 1258, 1259, 1260, 1261, 1262, 1263, 1264, 1265, 1266, 1267, 1268, 1269, 1270, 1271, 1272, 1273, 1274, 1275, 1276, 1277, 1278, 1279, 1280, 1281, 1282, 1283, 1284, 1285, 1286, 1287, 1288, 1289, 1290, 1291, 1292, 1293, 1294, 1295, 1296, 1297, 1298, 1299, 1300, 1301, 1302, 1303, 1304, 1305, 1306, 1307, 1308, 1309, 1310, 1311, 1312, 1313, 1314, 1315, 1316, 1317, 1318, 1319, 1320, 1321, 1322, 1323, 1324, 1325, 1326, 1327, 1328, 1329, 1330, 1331, 1332, 1333, 1334, 1335, 1336, 1337, 1338, 1339, 1340, 1341, 1342, 1343, 1344, 1345, 1346, 1347, 1348, 1349, 1350, 1351, 1352, 1353, 1354, 1355, 1356, 1357, 1358, 1359, 1360, 1361, 1362, 1363, 1364, 1365, 1366, 1367, 1368, 1369, 1370, 1371, 1372, 1373, 1374, 1375, 1376, 1377, 1378, 1379, 1380, 1381, 1382, 1383, 1384, 1385, 1386, 1387, 1388, 1389, 1390, 1391, 1392, 1393, 1394, 1395, 1396, 1397, 1398, 1399, 1400, 1401, 1402, 1403, 1404, 1405, 1406, 1407, 1408, 1409, 1410, 1411, 1412, 1413, 1414, 1415, 1416, 1417, 1418, 1419, 1420, 1421, 1422, 1423, 1424, 1425, 1426, 1427, 1428, 1429, 1430, 1431, 1432, 1433, 1434, 1435, 1436, 1437, 1438, 1439, 1440, 1441, 1442, 1443, 1444, 1445, 1446, 1447, 1448, 1449, 1450, 1451, 1452, 1453, 1454, 1455, 1456, 1457, 1458, 1459, 1460, 1461, 1462, 1463, 1464, 1465, 1466, 1467, 1468, 1469, 1470, 1471, 1472, 1473, 1474, 1475, 1476, 1477, 1478, 1479, 1480, 1481, 1482, 1483, 1484, 1485, 1486, 1487, 1488, 1489, 1490, 1491, 1492, 1493, 1494, 1495, 1496, 1497, 1498, 1499, 1500, 1501, 1502, 1503, 1504, 1505, 1506, 1507, 1508, 1509, 1510, 1511, 1512, 1513, 1514, 1515, 1516, 1517, 1518, 1519, 1520, 1521, 1522, 1523, 1524, 1525, 1526, 1527, 1528, 1529, 1530, 1531, 1532, 1533, 1534, 1535, 1536, 1537, 1538, 1539, 1540, 1541, 1542, 1543, 1544, 1545, 1546, 1547, 1548, 1549, 1550, 1551, 1552, 1553, 1554, 1555, 1556, 1557, 1558, 1559, 1560, 1561, 1562, 1563, 1564, 1565, 1566, 1567, 1568, 1569, 1570, 1571, 1572, 1573, 1574, 1575, 1576, 1577, 1578, 1579, 1580, 1581, 1582, 1583, 1584, 1585, 1586, 1587, 1588, 1589, 1590, 1591, 1592, 1593, 1594, 1595, 1596, 1597, 1598, 1599, 1600, 1601, 1602, 1603, 1604, 1605, 1606, 1607, 1608, 1609, 1610, 1611, 1612, 1613, 1614, 1615, 1616, 1617, 1618, 1619, 1620, 1621, 1622, 1623, 1624, 1625, 1626, 1627, 1628, 1629, 1630, 1631, 1632, 1633, 1634, 1635, 1636, 1637, 1638, 1639, 1640, 1641, 1642, 1643, 1644, 1645, 1646, 1647, 1648, 1649, 1650, 1651, 1652, 1653, 1654, 1655, 1656, 1657, 1658, 1659, 1660, 1661, 1662, 1663, 1664, 1665, 1666, 1667, 1668, 1669, 1670, 1671, 1672, 1673, 1674, 1675, 1676, 1677, 1678, 1679, 1680, 1681, 1682, 1683, 1684, 1685, 1686, 1687, 1688, 1689, 1690, 1691, 1692, 1693, 1694, 1695, 1696, 1697, 1698, 1699, 1700, 1701, 1702, 1703, 1704, 1705, 1706, 1707, 1708, 1709, 1710, 1711, 1712, 1713, 1714, 1715, 1716, 1717, 1718, 1719, 1720, 1721, 1722, 1723, 1724, 1725, 1726, 1727, 1728, 1729, 1730, 1731, 1732, 1733, 1734, 1735, 1736, 1737, 1738, 1739, 1740, 1741, 1742, 1743, 1744, 1745, 1746, 1747, 1748, 1749, 1750, 1751, 1752, 1753, 1754, 1755, 1756, 1757, 1758, 1759, 1760, 1761, 1762, 1763, 1764, 1765, 1766, 1767, 1768, 1769, 1770, 1771, 1772, 1773, 1774, 1775, 1776, 1777, 1778, 1779, 1780, 1781, 1782, 1783, 1784, 1785, 1786, 1787, 1788, 1789, 1790, 1791, 1792, 1793, 1794, 1795, 1796, 1797, 1798, 1799, 1800, 1801, 1802, 1803, 1804, 1805, 1806, 1807, 1808, 1809, 1810, 1811, 1812, 1813, 1814, 1815, 1816, 1817, 1818, 1819, 1820, 1821, 1822, 1823, 1824, 1825, 1826, 1827, 1828, 1829, 1830, 1831, 1832, 1833, 1834, 1835, 1836, 1837, 1838, 1839, 1840, 1841, 1842, 1843, 1844, 1845, 1846, 1847, 1848, 1849, 1850, 1851, 1852, 1853, 1854, 1855, 1856, 1857, 1858, 1859, 1860, 1861, 1862, 1863, 1864, 1865, 1866, 1867, 1868, 1869, 1870, 1871, 1872, 1873, 1874, 1875, 1876, 1877, 1878, 1879, 1880, 1881, 1882, 1883, 1884, 1885, 1886, 1887, 1888, 1889, 1890, 1891, 1892, 1893, 1894, 1895, 1896, 1897, 1898, 1899, 1900, 1901, 1902, 1903, 1904, 1905, 1906, 1907, 1908, 1909, 1910, 1911, 1912, 1913, 1914, 1915, 1916, 1917, 1918, 1919, 1920, 1921, 1922, 1923, 1924, 1925, 1926, 1927, 1928, 1929, 1930, 1931, 1932, 1933, 1934, 1935, 1936, 1937, 1938, 1939, 1940, 1941, 1942, 1943, 1944, 1945, 1946, 1947, 1948, 1949, 1950, 1951, 1952, 1953, 1954, 1955, 1956, 1957, 1958, 1959, 1960, 1961, 1962, 1963, 1964, 1965, 1966, 1967, 1968, 1969, 1970, 1971, 1972, 1973, 1974, 1975, 1976, 1977, 1978, 1979, 1980, 1981, 1982, 1983, 1984, 1985, 1986, 1987, 1988, 1989, 1990, 1991, 1992, 1993, 1994, 1995, 1996, 1997, 1998, 1999, 2000, 2001, 2002, 2003, 2004, 2005, 2006, 2007, 2008, 2009, 2010, 2011, 2012, 2013, 2014, 2015, 2016, 2017, 2018, 2019, 2020, 2021, 2022, 2023, 2024, 2025, 2026, 2027, 2028, 2029, 2030, 2031, 2032, 2033, 2034, 2035, 2036, 2037, 2038, 2039, 2040, 2041, 2042, 2043, 2044, 2045, 2046, 2047, 2048, 2049, 2050, 2051, 2052, 2053, 2054, 2055, 2056, 2057, 2058, 2059, 2060, 2061, 2062, 2063, 2064, 2065, 2066, 2067, 2068, 2069, 2070, 2071, 2072, 2073, 2074, 2075, 2076, 2077, 2078, 2079, 2080, 2081, 2082, 2083, 2084, 2085, 2086, 2087, 2088, 2089, 2090, 2091, 2092, 2093, 2094, 2095, 2096, 2097, 2098, 2099, 2100, 2101, 2102, 2103, 2104, 2105, 2106, 2107, 2108, 2109, 2110, 2111, 2112, 2113, 2114, 2115, 2116, 2117, 2118, 2119, 2120, 2121, 2122, 2123, 2124, 2125, 2126, 2127, 2128, 2129, 2130, 2131, 2132, 2133, 2134, 2135, 2136, 2137, 2138, 2139, 2140, 2141, 2142, 2143, 2144, 2145, 2146, 2147, 2148, 2149, 2150, 2151, 2152, 2153, 2154, 2155, 2156, 2157, 2158, 2159, 2160, 2161, 2162, 2163, 2164, 2165, 2166, 2167, 2168, 2169, 2170, 2171, 2172, 2173, 2174, 2175, 2176, 2177, 2178, 2179, 2180, 2181, 2182, 2183, 2184, 2185, 2186, 2187, 2188, 2189, 2190, 2191, 2192, 2193, 2194, 2195, 2196, 2197, 2198, 2199, 2200, 2201, 2202, 2203, 2204, 2205, 2206, 2207, 2208, 2209, 2210, 2211, 2212, 2213, 2214, 2215, 2216, 2217, 2218, 2219, 2220, 2221, 2222, 2223, 2224, 2225, 2226, 2227, 2228, 2229, 2230, 2231, 2232, 2233, 2234, 2235, 2236, 2237, 2238, 2239, 2240, 2241, 2242, 2243, 2244, 2245, 2246, 2247, 2248, 2249, 2250, 2251, 2252, 2253, 2254, 2255, 2256, 2257, 2258, 2259, 2260, 2261, 2262, 2263, 2264, 2265, 2266, 2267, 2268, 2269, 2270, 2271, 2272, 2273, 2274, 2275, 2276, 2277, 2278, 2279, 2280, 2281, 2282, 2283, 2284, 2285, 2286, 2287, 2288, 2289, 2290, 2291, 2292, 2293, 2294, 2295, 2296, 2297, 2298, 2299, 2300, 2301, 2302, 2303, 2304, 2305, 2306, 2307, 2308, 2309, 2310, 2311, 2312, 2313, 2314, 2315, 2316, 2317, 2318, 2319, 2320, 2321, 2322, 2323, 2324, 2325, 2326, 2327, 2328, 2329, 2330, 2331, 2332, 2333, 2334, 2335, 2336, 2337, 2338, 2339, 2340, 2341, 2342, 2343, 2344, 2345, 2346, 2347, 2348, 2349, 2350, 2351, 2352, 2353, 2354, 2355, 2356, 2357, 2358, 2359, 2360, 2361, 2362, 2363, 2364, 2365, 2366, 2367, 2368, 2369, 2370, 2371, 2372, 2373, 2374, 2375, 2376, 2377, 2378, 2379, 2380, 2381, 2382, 2383, 2384, 2385, 2386, 2387, 2388, 2389, 2390, 2391, 2392, 2393, 2394, 2395, 2396, 2397, 2398, 2399, 2400, 2401, 2402, 2403, 2404, 2405, 2406, 2407, 2408, 2409, 2410, 2411, 2412, 2413, 2414, 2415, 2416, 2417, 2418, 2419, 2420, 2421, 2422, 2423, 2424, 2425, 2426, 2427, 2428, 2429, 2430, 2431, 2432, 2433, 2434, 2435, 2436, 2437, 2438, 2439, 2440, 2441, 2442, 2443, 2444, 2445, 2446, 2447, 2448, 2449, 2450, 2451, 2452, 2453, 2454, 2455, 2456, 2457, 2458, 2459, 2460, 2461, 2462, 2463, 2464, 2465, 2466, 2467, 2468, 2469, 2470, 2471, 2472, 2473, 2474, 2475, 2476, 2477, 2478, 2479, 2480, 2481, 2482, 2483, 2484, 2485, 2486, 2487, 2488, 2489, 2490, 2491, 2492, 2493, 2494, 2495, 2496, 2497, 2498, 2499, 2500, 2501, 2502, 2503, 2504, 2505, 2506, 2507, 2508, 2509, 2510, 2511, 2512, 2513, 2514, 2515, 2516, 2517, 2518, 2519, 2520, 2521, 2522, 2523, 2524, 2525, 2526, 2527, 2528, 2529, 2530, 2531, 2532, 2533, 2534, 2535, 2536, 2537, 2538, 2539, 2540, 2541, 2542, 2543, 2544, 2545, 2546, 2547, 2548, 2549, 2550, 2551, 2552, 2553, 2554, 2555, 2556, 2557, 2558, 2559, 2560, 2561, 2562, 2563, 2564, 2565, 2566, 2567, 2568, 2569, 2570, 2571, 2572, 2573, 2574, 2575, 2576, 2577, 2578, 2579, 2580, 2581, 2582, 2583, 2584, 2585, 2586, 2587, 2588, 2589, 2590, 2591, 2592, 2593, 2594, 2595, 2596, 2597, 2598, 2599, 2600, 2601, 2602, 2603, 2604, 2605, 2606, 2607, 2608, 2609, 2610, 2611, 2612, 2613, 2614, 2615, 2616, 2617, 2618, 2619, 2620, 2621, 2622, 2623, 2624, 2625, 2626, 2627, 2628, 2629, 2630, 2631, 2632, 2633, 2634, 2635, 2636, 2637, 2638, 2639, 2640, 2641, 2642, 2643, 2644, 2645, 2646, 2647, 2648, 2649, 2650, 2651, 2652, 2653, 2654, 2655, 2656, 2657, 2658, 2659, 2660, 2661, 2662, 2663, 2664, 2665, 2666, 2667, 2668, 2669, 2670, 2671, 2672, 2673, 2674, 2675, 2676, 2677, 2678, 2679, 2680, 2681, 2682, 2683, 2684, 2685, 2686, 2687, 2688, 2689, 2690, 2691, 2692, 2693, 2694, 2695, 2696, 2697, 2698, 2699, 2700, 2701, 2702, 2703, 2704, 2705, 2706, 2707, 2708, 2709, 2710, 2711, 2712, 2713, 2714, 2715, 2716, 2717, 2718, 2719, 2720, 2721, 2722, 2723, 2724, 2725, 2726, 2727, 2728, 2729, 2730, 2731, 2732, 2733, 2734, 2735, 2736, 2737, 2738, 2739, 2740, 2741, 2742, 2743, 2744, 2745, 2746, 2747, 2748, 2749, 2750, 2751, 2752, 2753, 2754, 2755, 2756, 2757, 2758, 2759, 2760, 2761, 2762, 2763, 2764, 2765, 2766, 2767, 2768, 2769, 2770, 2771, 2772, 2773, 2774, 2775, 2776, 2777, 2778, 2779, 2780, 2781, 2782, 2783, 2784, 2785, 2786, 2787, 2788, 2789, 2790, 2791, 2792, 2793, 2794, 2795, 2796, 2797, 2798, 2799, 2800, 2801, 2802, 2803, 2804, 2805, 2806, 2807, 2808, 2809, 2810, 2811, 2812, 2813, 2814, 2815, 2816, 2817, 2818, 2819, 2820, 2821, 2822, 2823, 2824, 2825, 2826, 2827, 2828, 2829, 2830, 2831, 2832, 2833, 2834, 2835, 2836, 2837, 2838, 2839, 2840, 2841, 2842, 2843, 2844, 2845, 2846, 2847, 2848, 2849, 2850, 2851, 2852, 2853, 2854, 2855, 2856, 2857, 2858, 2859, 2860, 2861, 2862, 2863, 2864, 2865, 2866, 2867, 2868, 2869, 2870, 2871, 2872, 2873, 2874, 2875, 2876, 2877, 2878, 2879, 2880, 2881, 2882, 2883, 2884, 2885, 2886, 2887, 2888, 2889, 2890, 2891, 2892, 2893, 2894, 2895, 2896, 2897, 2898, 2899, 2900, 2901, 2902, 2903, 2904, 2905, 2906, 2907, 2908, 2909, 2910, 2911, 2912, 2913, 2914, 2915, 2916, 2917, 2918, 2919, 2920, 2921, 2922, 2923, 2924, 2925, 2926, 2927, 2928, 2929, 2930, 2931, 2932, 2933, 2934, 2935, 2936, 2937, 2938, 2939, 2940, 2941, 2942, 2943, 2944, 2945, 2946, 2947, 2948, 2949, 2950, 2951, 2952, 2953, 2954, 2955, 2956, 2957, 2958, 2959, 2960, 2961, 2962, 2963, 2964, 2965, 2966, 2967, 2968, 2969, 2970, 2971, 2972, 2973, 2974, 2975, 2976, 2977, 2978, 2979, 2980, 2981, 2982, 2983, 2984, 2985, 2986, 2987, 2988, 2989, 2990, 2991, 2992, 2993, 2994, 2995, 2996, 2997, 2998, 2999, 3000, 3001, 3002, 3003, 3004, 3005, 3006, 3007, 3008, 3009, 3010, 3011, 3012, 3013, 3014, 3015, 3016, 3017, 3018, 3019, 3020, 3021, 3022, 3023, 3024, 3025, 3026, 3027, 3028, 3029, 3030, 3031, 3032, 3033, 3034, 3035, 3036, 3037, 3038, 3039, 3040, 3041, 3042, 3043, 3044, 3045, 3046, 3047, 3048, 3049, 3050, 3051, 3052, 3053, 3054, 3055, 3056, 3057, 3058, 3059, 3060, 3061, 3062, 3063, 3064, 3065, 3066, 3067, 3068, 3069, 3070, 3071, 3072, 3073, 3074, 3075, 3076, 3077, 3078, 3079, 3080, 3081, 3082, 3083, 3084, 3085, 3086, 3087, 3088, 3089, 3090, 3091, 3092, 3093, 3094, 3095, 3096, 3097, 3098, 3099, 3100, 3101, 3102, 3103, 3104, 3105, 3106, 3107, 3108, 3109, 3110, 3111, 3112, 3113, 3114, 3115, 3116, 3117, 3118, 3119, 3120, 3121, 3122, 3123, 3124, 3125, 3126, 3127, 3128, 3129, 3130, 3131, 3132, 3133, 3134, 3135, 3136, 3137, 3138, 3139, 3140, 3141, 3142, 3143, 3144, 3145, 3146, 3147, 3148, 3149, 3150, 3151, 3152, 3153, 3154, 3155, 3156, 3157, 3158, 3159, 3160, 3161, 3162, 3163, 3164, 3165, 3166, 3167, 3168, 3169, 3170, 3171, 3172, 3173, 3174, 3175, 3176, 3177, 3178, 3179, 3180, 3181, 3182, 3183, 3184, 3185, 3186, 3187, 3188, 3189, 3190, 3191, 3192, 3193, 3194, 3195, 3196, 3197, 3198, 3199, 3200, 3201, 3202, 3203, 3204, 3205, 3206, 3207, 3208, 3209, 3210, 3211, 3212, 3213, 3214, 3215, 3216, 3217, 3218, 3219, 3220, 3221, 3222, 3223, 3224, 3225, 3226, 3227, 3228, 3229, 3230, 3231, 3232, 3233, 3234, 3235, 3236, 3237, 3238, 3239, 3240, 3241, 3242, 3243, 3244, 3245, 3246, 3247, 3248, 3249, 3250, 3251, 3252, 3253, 3254, 3255, 3256, 3257, 3258, 3259, 3260, 3261, 3262, 3263, 3264, 3265, 3266, 3267, 3268, 3269, 3270, 3271, 3272, 3273, 3274, 3275, 3276, 3277, 3278, 3279, 3280, 3281, 3282, 3283, 3284, 3285, 3286, 3287, 3288, 3289, 3290, 3291, 3292, 3293, 3294, 3295, 3296, 3297, 3298, 3299, 3300, 3301, 3302, 3303, 3304, 3305, 3306, 3307, 3308, 3309, 3310, 3311, 3312, 3313, 3314, 3315, 3316, 3317, 3318, 3319, 3320, 3321, 3322, 3323, 3324, 3325, 3326, 3327, 3328, 3329, 3330, 3331, 3332, 3333, 3334, 3335, 3336, 3337, 3338, 3339, 3340, 3341, 3342, 3343, 3344, 3345, 3346, 3347, 3348, 3349, 3350, 3351, 3352, 3353, 3354, 3355, 3356, 3357, 3358, 3359, 3360, 3361, 3362, 3363, 3364, 3365, 3366, 3367, 3368, 3369, 3370, 3371, 3372, 3373, 3374, 3375, 3376, 3377, 3378, 3379, 3380, 3381, 3382, 3383, 3384, 3385, 3386, 3387, 3388, 3389, 3390, 3391, 3392, 3393, 3394, 3395, 3396, 3397, 3398, 3399, 3400, 3401, 3402, 3403, 3404, 3405, 3406, 3407, 3408, 3409, 3410, 3411, 3412, 3413, 3414, 3415, 3416, 3417, 3418, 3419, 3420, 3421, 3422, 3423, 3424, 3425, 3426, 3427, 3428, 3429, 3430, 3431, 3432, 3433, 3434, 3435, 3436, 3437, 3438, 3439, 3440, 3441, 3442, 3443, 3444, 3445, 3446, 3447, 3448, 3449, 3450, 3451, 3452, 3453, 3454, 3455, 3456, 3457, 3458, 3459, 3460, 3461, 3462, 3463, 3464, 3465, 3466, 3467, 3468, 3469, 3470, 3471, 3472, 3473, 3474, 3475, 3476, 3477, 3478, 3479, 3480, 3481, 3482, 3483, 3484, 3485, 3486, 3487, 3488, 3489, 3490, 3491, 3492, 3493, 3494, 3495, 3496, 3497, 3498, 3499, 3500, 3501, 3502, 3503, 3504, 3505, 3506, 3507, 3508, 3509, 3510, 3511, 3512, 3513, 3514, 3515, 3516, 3517, 3518, 3519, 3520, 3521, 3522, 3523, 3524, 3525, 3526, 3527, 3528, 3529, 3530, 3531, 3532, 3533, 3534, 3535, 3536, 3537, 3538, 3539, 3540, 3541, 3542, 3543, 3544, 3545, 3546, 3547, 3548, 3549, 3550, 3551, 3552, 3553, 3554, 3555, 3556, 3557, 3558, 3559, 3560, 3561, 3562, 3563, 3564, 3565, 3566, 3567, 3568, 3569, 3570, 3571, 3572, 3573, 3574, 3575, 3576, 3577, 3578, 3579, 3580, 3581, 3582, 3583, 3584, 3585, 3586, 3587, 3588, 3589, 3590, 3591, 3592, 3593, 3594, 3595, 3596, 3597, 3598, 3599, 3600, 3601, 3602, 3603, 3604, 3605, 3606, 3607, 3608, 3609, 3610, 3611, 3612, 3613, 3614, 3615, 3616, 3617, 3618, 3619, 3620, 3621, 3622, 3623, 3624, 3625, 3626, 3627, 3628, 3629, 3630, 3631, 3632, 3633, 3634, 3635, 3636, 3637, 3638, 3639, 3640, 3641, 3642, 3643, 3644, 3645, 3646, 3647, 3648, 3649, 3650, 3651, 3652, 3653, 3654, 3655, 3656, 3657, 3658, 3659, 3660, 3661, 3662, 3663, 3664, 3665, 3666, 3667, 3668, 3669, 3670, 3671, 3672, 3673, 3674, 3675, 3676, 3677, 3678, 3679, 3680, 3681, 3682, 3683, 3684, 3685, 3686, 3687, 3688, 3689, 3690, 3691, 3692, 3693, 3694, 3695, 3696, 3697, 3698, 3699, 3700, 3701, 3702, 3703, 3704, 3705, 3706, 3707, 3708, 3709, 3710, 3711, 3712, 3713, 3714, 3715, 3716, 3717, 3718, 3719, 3720, 3721, 3722, 3723, 3724, 3725, 3726, 3727, 3728, 3729, 3730, 3731, 3732, 3733, 3734, 3735, 3736, 3737, 3738, 3739, 3740, 3741, 3742, 3743, 3744, 3745, 3746, 3747, 3748, 3749, 3750, 3751, 3752, 3753, 3754, 3755, 3756, 3757, 3758, 3759, 3760, 3761, 3762, 3763, 3764, 3765, 3766, 3767, 3768, 3769, 3770, 3771, 3772, 3773, 3774, 3775, 3776, 3777, 3778, 3779, 3780, 3781, 3782, 3783, 3784, 3785, 3786, 3787, 3788, 3789, 3790, 3791, 3792, 3793, 3794, 3795, 3796, 3797, 3798, 3799, 3800, 3801, 3802, 3803, 3804, 3805, 3806, 3807, 3808, 3809, 3810, 3811, 3812, 3813, 3814, 3815, 3816, 3817, 3818, 3819, 3820, 3821, 3822, 3823, 3824, 3825, 3826, 3827, 3828, 3829, 3830, 3831, 3832, 3833, 3834, 3835, 3836, 3837, 3838, 3839, 3840, 3841, 3842, 3843, 3844, 3845, 3846, 3847, 3848, 3849, 3850, 3851, 3852, 3853, 3854, 3855, 3856, 3857, 3858, 3859, 3860, 3861, 3862, 3863, 3864, 3865, 3866, 3867, 3868, 3869, 3870, 3871, 3872, 3873, 3874, 3875, 3876, 3877, 3878, 3879, 3880, 3881, 3882, 3883, 3884, 3885, 3886, 3887, 3888, 3889, 3890, 3891, 3892, 3893, 3894, 3895, 3896, 3897, 3898, 3899, 3900, 3901, 3902, 3903, 3904, 3905, 3906, 3907, 3908, 3909, 3910, 3911, 3912, 3913, 3914, 3915, 3916, 3917, 3918, 3919, 3920, 3921, 3922, 3923, 3924, 3925, 3926, 3927, 3928, 3929, 3930, 3931, 3932, 3933, 3934, 3935, 3936, 3937, 3938, 3939, 3940, 3941, 3942, 3943, 3944, 3945, 3946, 3947, 3948, 3949, 3950, 3951, 3952, 3953, 3954, 3955, 3956, 3957, 3958, 3959, 3960, 3961, 3962, 3963, 3964, 3965, 3966, 3967, 3968, 3969, 3970, 3971, 3972, 3973, 3974, 3975, 3976, 3977, 3978, 3979, 3980, 3981, 3982, 3983, 3984, 3985, 3986, 3987, 3988, 3989, 3990, 3991, 3992, 3993, 3994, 3995, 3996, 3997, 3998, 3999, 4000, 4001, 4002, 4003, 4004, 4005, 4006, 4007, 4008, 4009, 4010, 4011, 4012, 4013, 4014, 4015, 4016, 4017, 4018, 4019, 4020, 4021, 4022, 4023, 4024, 4025, 4026, 4027, 4028, 4029, 4030, 4031, 4032, 4033, 4034, 4035, 4036, 4037, 4038, 4039, 4040, 4041, 4042, 4043, 4044, 4045, 4046, 4047, 4048, 4049, 4050, 4051, 4052, 4053, 4054, 4055, 4056, 4057, 4058, 4059, 4060, 4061, 4062, 4063, 4064, 4065, 4066, 4067, 4068, 4069, 4070, 4071, 4072, 4073, 4074, 4075, 4076, 4077, 4078, 4079, 4080, 4081, 4082, 4083, 4084, 4085, 4086, 4087, 4088, 4089, 4090, 4091, 4092, 4093, 4094, 4095, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 256, 257, 258, 259, 260, 261, 262, 263, 264, 265, 266, 267, 268, 269, 270, 271, 272, 273, 274, 275, 276, 277, 278, 279, 280, 281, 282, 283, 284, 285, 286, 287, 288, 289, 290, 291, 292, 293, 294, 295, 296, 297, 298, 299, 300, 301, 302, 303, 304, 305, 306, 307, 308, 309, 310, 311, 312, 313, 314, 315, 316, 317, 318, 319, 320, 321, 322, 323, 324, 325, 326, 327, 328, 329, 330, 331, 332, 333, 334, 335, 336, 337, 338, 339, 340, 341, 342, 343, 344, 345, 346, 347, 348, 349, 350, 351, 352, 353, 354, 355, 356, 357, 358, 359, 360, 361, 362, 363, 364, 365, 366, 367, 368, 369, 370, 371, 372, 373, 374, 375, 376, 377, 378, 379, 380, 381, 382, 383, 384, 385, 386, 387, 388, 389, 390, 391, 392, 393, 394, 395, 396, 397, 398, 399, 400, 401, 402, 403, 404, 405, 406, 407, 408, 409, 410, 411, 412, 413, 414, 415, 416, 417, 418, 419, 420, 421, 422, 423, 424, 425, 426, 427, 428, 429, 430, 431, 432, 433, 434, 435, 436, 437, 438, 439, 440, 441, 442, 443, 444, 445, 446, 447, 448, 449, 450, 451, 452, 453, 454, 455, 456, 457, 458, 459, 460, 461, 462, 463, 464, 465, 466, 467, 468, 469, 470, 471, 472, 473, 474, 475, 476, 477, 478, 479, 480, 481, 482, 483, 484, 485, 486, 487, 488, 489, 490, 491, 492, 493, 494, 495, 496, 497, 498, 499, 500, 501, 502, 503, 504, 505, 506, 507, 508, 509, 510, 511, 512, 513, 514, 515, 516, 517, 518, 519, 520, 521, 522, 523, 524, 525, 526, 527, 528, 529, 530, 531, 532, 533, 534, 535, 536, 537, 538, 539, 540, 541, 542, 543, 544, 545, 546, 547, 548, 549, 550, 551, 552, 553, 554, 555, 556, 557, 558, 559, 560, 561, 562, 563, 564, 565, 566, 567, 568, 569, 570, 571, 572, 573, 574, 575, 576, 577, 578, 579, 580, 581, 582, 583, 584, 585, 586, 587, 588, 589, 590, 591, 592, 593, 594, 595, 596, 597, 598, 599, 600, 601, 602, 603, 604, 605, 606, 607, 608, 609, 610, 611, 612, 613, 614, 615, 616, 617, 618, 619, 620, 621, 622, 623, 624, 625, 626, 627, 628, 629, 630, 631, 632, 633, 634, 635, 636, 637, 638, 639, 640, 641, 642, 643, 644, 645, 646, 647, 648, 649, 650, 651, 652, 653, 654, 655, 656, 657, 658, 659, 660, 661, 662, 663, 664, 665, 666, 667, 668, 669, 670, 671, 672, 673, 674, 675, 676, 677, 678, 679, 680, 681, 682, 683, 684, 685, 686, 687, 688, 689, 690, 691, 692, 693, 694, 695, 696, 697, 698, 699, 700, 701, 702, 703, 704, 705, 706, 707, 708, 709, 710, 711, 712, 713, 714, 715, 716, 717, 718, 719, 720, 721, 722, 723, 724, 725, 726, 727, 728, 729, 730, 731, 732, 733, 734, 735, 736, 737, 738, 739, 740, 741, 742, 743, 744, 745, 746, 747, 748, 749, 750, 751, 752, 753, 754, 755, 756, 757, 758, 759, 760, 761, 762, 763, 764, 765, 766, 767, 768, 769, 770, 771, 772, 773, 774, 775, 776, 777, 778, 779, 780, 781, 782, 783, 784, 785, 786, 787, 788, 789, 790, 791, 792, 793, 794, 795, 796, 797, 798, 799, 800, 801, 802, 803, 804, 805, 806, 807, 808, 809, 810, 811, 812, 813, 814, 815, 816, 817, 818, 819, 820, 821, 822, 823, 824, 825, 826, 827, 828, 829, 830, 831, 832, 833, 834, 835, 836, 837, 838, 839, 840, 841, 842, 843, 844, 845, 846, 847, 848, 849, 850, 851, 852, 853, 854, 855, 856, 857, 858, 859, 860, 861, 862, 863, 864, 865, 866, 867, 868, 869, 870, 871, 872, 873, 874, 875, 876, 877, 878, 879, 880, 881, 882, 883, 884, 885, 886, 887, 888, 889, 890, 891, 892, 893, 894, 895, 896, 897, 898, 899, 900, 901, 902, 903, 904, 905, 906, 907, 908, 909, 910, 911, 912, 913, 914, 915, 916, 917, 918, 919, 920, 921, 922, 923, 924, 925, 926, 927, 928, 929, 930, 931, 932, 933, 934, 935, 936, 937, 938, 939, 940, 941, 942, 943, 944, 945, 946, 947, 948, 949, 950, 951, 952, 953, 954, 955, 956, 957, 958, 959, 960, 961, 962, 963, 964, 965, 966, 967, 968, 969, 970, 971, 972, 973, 974, 975, 976, 977, 978, 979, 980, 981, 982, 983, 984, 985, 986, 987, 988, 989, 990, 991, 992, 993, 994, 995, 996, 997, 998, 999, 1000, 1001, 1002, 1003, 1004, 1005, 1006, 1007, 1008, 1009, 1010, 1011, 1012, 1013, 1014, 1015, 1016, 1017, 1018, 1019, 1020, 1021, 1022, 1023, 1024, 1025, 1026, 1027, 1028, 1029, 1030, 1031, 1032, 1033, 1034, 1035, 1036, 1037, 1038, 1039, 1040, 1041, 1042, 1043, 1044, 1045, 1046, 1047, 1048, 1049, 1050, 1051, 1052, 1053, 1054, 1055, 1056, 1057, 1058, 1059, 1060, 1061, 1062, 1063, 1064, 1065, 1066, 1067, 1068, 1069, 1070, 1071, 1072, 1073, 1074, 1075, 1076, 1077, 1078, 1079, 1080, 1081, 1082, 1083, 1084, 1085, 1086, 1087, 1088, 1089, 1090, 1091, 1092, 1093, 1094, 1095, 1096, 1097, 1098, 1099, 1100, 1101, 1102, 1103, 1104, 1105, 1106, 1107, 1108, 1109, 1110, 1111, 1112, 1113, 1114, 1115, 1116, 1117, 1118, 1119, 1120, 1121, 1122, 1123, 1124, 1125, 1126, 1127, 1128, 1129, 1130, 1131, 1132, 1133, 1134, 1135, 1136, 1137, 1138, 1139, 1140, 1141, 1142, 1143, 1144, 1145, 1146, 1147, 1148, 1149, 1150, 1151, 1152, 1153, 1154, 1155, 1156, 1157, 1158, 1159, 1160, 1161, 1162, 1163, 1164, 1165, 1166, 1167, 1168, 1169, 1170, 1171, 1172, 1173, 1174, 1175, 1176, 1177, 1178, 1179, 1180, 1181, 1182, 1183, 1184, 1185, 1186, 1187, 1188, 1189, 1190, 1191, 1192, 1193, 1194, 1195, 1196, 1197, 1198, 1199, 1200, 1201, 1202, 1203, 1204, 1205, 1206, 1207, 1208, 1209, 1210, 1211, 1212, 1213, 1214, 1215, 1216, 1217, 1218, 1219, 1220, 1221, 1222, 1223, 1224, 1225, 1226, 1227, 1228, 1229, 1230, 1231, 1232, 1233, 1234, 1235, 1236, 1237, 1238, 1239, 1240, 1241, 1242, 1243, 1244, 1245, 1246, 1247, 1248, 1249, 1250, 1251, 1252, 1253, 1254, 1255, 1256, 1257, 1258, 1259, 1260, 1261, 1262, 1263, 1264, 1265, 1266, 1267, 1268, 1269, 1270, 1271, 1272, 1273, 1274, 1275, 1276, 1277, 1278, 1279, 1280, 1281, 1282, 1283, 1284, 1285, 1286, 1287, 1288, 1289, 1290, 1291, 1292, 1293, 1294, 1295, 1296, 1297, 1298, 1299, 1300, 1301, 1302, 1303, 1304, 1305, 1306, 1307, 1308, 1309, 1310, 1311, 1312, 1313, 1314, 1315, 1316, 1317, 1318, 1319, 1320, 1321, 1322, 1323, 1324, 1325, 1326, 1327, 1328, 1329, 1330, 1331, 1332, 1333, 1334, 1335, 1336, 1337, 1338, 1339, 1340, 1341, 1342, 1343, 1344, 1345, 1346, 1347, 1348, 1349, 1350, 1351, 1352, 1353, 1354, 1355, 1356, 1357, 1358, 1359, 1360, 1361, 1362, 1363, 1364, 1365, 1366, 1367, 1368, 1369, 1370, 1371, 1372, 1373, 1374, 1375, 1376, 1377, 1378, 1379, 1380, 1381, 1382, 1383, 1384, 1385, 1386, 1387, 1388, 1389, 1390, 1391, 1392, 1393, 1394, 1395, 1396, 1397, 1398, 1399, 1400, 1401, 1402, 1403, 1404, 1405, 1406, 1407, 1408, 1409, 1410, 1411, 1412, 1413, 1414, 1415, 1416, 1417, 1418, 1419, 1420, 1421, 1422, 1423, 1424, 1425, 1426, 1427, 1428, 1429, 1430, 1431, 1432, 1433, 1434, 1435, 1436, 1437, 1438, 1439, 1440, 1441, 1442, 1443, 1444, 1445, 1446, 1447, 1448, 1449, 1450, 1451, 1452, 1453, 1454, 1455, 1456, 1457, 1458, 1459, 1460, 1461, 1462, 1463, 1464, 1465, 1466, 1467, 1468, 1469, 1470, 1471, 1472, 1473, 1474, 1475, 1476, 1477, 1478, 1479, 1480, 1481, 1482, 1483, 1484, 1485, 1486, 1487, 1488, 1489, 1490, 1491, 1492, 1493, 1494, 1495, 1496, 1497, 1498, 1499, 1500, 1501, 1502, 1503, 1504, 1505, 1506, 1507, 1508, 1509, 1510, 1511, 1512, 1513, 1514, 1515, 1516, 1517, 1518, 1519, 1520, 1521, 1522, 1523, 1524, 1525, 1526, 1527, 1528, 1529, 1530, 1531, 1532, 1533, 1534, 1535, 1536, 1537, 1538, 1539, 1540, 1541, 1542, 1543, 1544, 1545, 1546, 1547, 1548, 1549, 1550, 1551, 1552, 1553, 1554, 1555, 1556, 1557, 1558, 1559, 1560, 1561, 1562, 1563, 1564, 1565, 1566, 1567, 1568, 1569, 1570, 1571, 1572, 1573, 1574, 1575, 1576, 1577, 1578, 1579, 1580, 1581, 1582, 1583, 1584, 1585, 1586, 1587, 1588, 1589, 1590, 1591, 1592, 1593, 1594, 1595, 1596, 1597, 1598, 1599, 1600, 1601, 1602, 1603, 1604, 1605, 1606, 1607, 1608, 1609, 1610, 1611, 1612, 1613, 1614, 1615, 1616, 1617, 1618, 1619, 1620, 1621, 1622, 1623, 1624, 1625, 1626, 1627, 1628, 1629, 1630, 1631, 1632, 1633, 1634, 1635, 1636, 1637, 1638, 1639, 1640, 1641, 1642, 1643, 1644, 1645, 1646, 1647, 1648, 1649, 1650, 1651, 1652, 1653, 1654, 1655, 1656, 1657, 1658, 1659, 1660, 1661, 1662, 1663, 1664, 1665, 1666, 1667, 1668, 1669, 1670, 1671, 1672, 1673, 1674, 1675, 1676, 1677, 1678, 1679, 1680, 1681, 1682, 1683, 1684, 1685, 1686, 1687, 1688, 1689, 1690, 1691, 1692, 1693, 1694, 1695, 1696, 1697, 1698, 1699, 1700, 1701, 1702, 1703, 1704, 1705, 1706, 1707, 1708, 1709, 1710, 1711, 1712, 1713, 1714, 1715, 1716, 1717, 1718, 1719, 1720, 1721, 1722, 1723, 1724, 1725, 1726, 1727, 1728, 1729, 1730, 1731, 1732, 1733, 1734, 1735, 1736, 1737, 1738, 1739, 1740, 1741, 1742, 1743, 1744, 1745, 1746, 1747, 1748, 1749, 1750, 1751, 1752, 1753, 1754, 1755, 1756, 1757, 1758, 1759, 1760, 1761, 1762, 1763, 1764, 1765, 1766, 1767, 1768, 1769, 1770, 1771, 1772, 1773, 1774, 1775, 1776, 1777, 1778, 1779, 1780, 1781, 1782, 1783, 1784, 1785, 1786, 1787, 1788, 1789, 1790, 1791, 1792, 1793, 1794, 1795, 1796, 1797, 1798, 1799, 1800, 1801, 1802, 1803, 1804, 1805, 1806, 1807, 1808, 1809, 1810, 1811, 1812, 1813, 1814, 1815, 1816, 1817, 1818, 1819, 1820, 1821, 1822, 1823, 1824, 1825, 1826, 1827, 1828, 1829, 1830, 1831, 1832, 1833, 1834, 1835, 1836, 1837, 1838, 1839, 1840, 1841, 1842, 1843, 1844, 1845, 1846, 1847, 1848, 1849, 1850, 1851, 1852, 1853, 1854, 1855, 1856, 1857, 1858, 1859, 1860, 1861, 1862, 1863, 1864, 1865, 1866, 1867, 1868, 1869, 1870, 1871, 1872, 1873, 1874, 1875, 1876, 1877, 1878, 1879, 1880, 1881, 1882, 1883, 1884, 1885, 1886, 1887, 1888, 1889, 1890, 1891, 1892, 1893, 1894, 1895, 1896, 1897, 1898, 1899, 1900, 1901, 1902, 1903, 1904, 1905, 1906, 1907, 1908, 1909, 1910, 1911, 1912, 1913, 1914, 1915, 1916, 1917, 1918, 1919, 1920, 1921, 1922, 1923, 1924, 1925, 1926, 1927, 1928, 1929, 1930, 1931, 1932, 1933, 1934, 1935, 1936, 1937, 1938, 1939, 1940, 1941, 1942, 1943, 1944, 1945, 1946, 1947, 1948, 1949, 1950, 1951, 1952, 1953, 1954, 1955, 1956, 1957, 1958, 1959, 1960, 1961, 1962, 1963, 1964, 1965, 1966, 1967, 1968, 1969, 1970, 1971, 1972, 1973, 1974, 1975, 1976, 1977, 1978, 1979, 1980, 1981, 1982, 1983, 1984, 1985, 1986, 1987, 1988, 1989, 1990, 1991, 1992, 1993, 1994, 1995, 1996, 1997, 1998, 1999, 2000, 2001, 2002, 2003, 2004, 2005, 2006, 2007, 2008, 2009, 2010, 2011, 2012, 2013, 2014, 2015, 2016, 2017, 2018, 2019, 2020, 2021, 2022, 2023, 2024, 2025, 2026, 2027, 2028, 2029, 2030, 2031, 2032, 2033, 2034, 2035, 2036, 2037, 2038, 2039, 2040, 2041, 2042, 2043, 2044, 2045, 2046, 2047, 2048, 2049, 2050, 2051, 2052, 2053, 2054, 2055, 2056, 2057, 2058, 2059, 2060, 2061, 2062, 2063, 2064, 2065, 2066, 2067, 2068, 2069, 2070, 2071, 2072, 2073, 2074, 2075, 2076, 2077, 2078, 2079, 2080, 2081, 2082, 2083, 2084, 2085, 2086, 2087, 2088, 2089, 2090, 2091, 2092, 2093, 2094, 2095, 2096, 2097, 2098, 2099, 2100, 2101, 2102, 2103, 2104, 2105, 2106, 2107, 2108, 2109, 2110, 2111, 2112, 2113, 2114, 2115, 2116, 2117, 2118, 2119, 2120, 2121, 2122, 2123, 2124, 2125, 2126, 2127, 2128, 2129, 2130, 2131, 2132, 2133, 2134, 2135, 2136, 2137, 2138, 2139, 2140, 2141, 2142, 2143, 2144, 2145, 2146, 2147, 2148, 2149, 2150, 2151, 2152, 2153, 2154, 2155, 2156, 2157, 2158, 2159, 2160, 2161, 2162, 2163, 2164, 2165, 2166, 2167, 2168, 2169, 2170, 2171, 2172, 2173, 2174, 2175, 2176, 2177, 2178, 2179, 2180, 2181, 2182, 2183, 2184, 2185, 2186, 2187, 2188, 2189, 2190, 2191, 2192, 2193, 2194, 2195, 2196, 2197, 2198, 2199, 2200, 2201, 2202, 2203, 2204, 2205, 2206, 2207, 2208, 2209, 2210, 2211, 2212, 2213, 2214, 2215, 2216, 2217, 2218, 2219, 2220, 2221, 2222, 2223, 2224, 2225, 2226, 2227, 2228, 2229, 2230, 2231, 2232, 2233, 2234, 2235, 2236, 2237, 2238, 2239, 2240, 2241, 2242, 2243, 2244, 2245, 2246, 2247, 2248, 2249, 2250, 2251, 2252, 2253, 2254, 2255, 2256, 2257, 2258, 2259, 2260, 2261, 2262, 2263, 2264, 2265, 2266, 2267, 2268, 2269, 2270, 2271, 2272, 2273, 2274, 2275, 2276, 2277, 2278, 2279, 2280, 2281, 2282, 2283, 2284, 2285, 2286, 2287, 2288, 2289, 2290, 2291, 2292, 2293, 2294, 2295, 2296, 2297, 2298, 2299, 2300, 2301, 2302, 2303, 2304, 2305, 2306, 2307, 2308, 2309, 2310, 2311, 2312, 2313, 2314, 2315, 2316, 2317, 2318, 2319, 2320, 2321, 2322, 2323, 2324, 2325, 2326, 2327, 2328, 2329, 2330, 2331, 2332, 2333, 2334, 2335, 2336, 2337, 2338, 2339, 2340, 2341, 2342, 2343, 2344, 2345, 2346, 2347, 2348, 2349, 2350, 2351, 2352, 2353, 2354, 2355, 2356, 2357, 2358, 2359, 2360, 2361, 2362, 2363, 2364, 2365, 2366, 2367, 2368, 2369, 2370, 2371, 2372, 2373, 2374, 2375, 2376, 2377, 2378, 2379, 2380, 2381, 2382, 2383, 2384, 2385, 2386, 2387, 2388, 2389, 2390, 2391, 2392, 2393, 2394, 2395, 2396, 2397, 2398, 2399, 2400, 2401, 2402, 2403, 2404, 2405, 2406, 2407, 2408, 2409, 2410, 2411, 2412, 2413, 2414, 2415, 2416, 2417, 2418, 2419, 2420, 2421, 2422, 2423, 2424, 2425, 2426, 2427, 2428, 2429, 2430, 2431, 2432, 2433, 2434, 2435, 2436, 2437, 2438, 2439, 2440, 2441, 2442, 2443, 2444, 2445, 2446, 2447, 2448, 2449, 2450, 2451, 2452, 2453, 2454, 2455, 2456, 2457, 2458, 2459, 2460, 2461, 2462, 2463, 2464, 2465, 2466, 2467, 2468, 2469, 2470, 2471, 2472, 2473, 2474, 2475, 2476, 2477, 2478, 2479, 2480, 2481, 2482, 2483, 2484, 2485, 2486, 2487, 2488, 2489, 2490, 2491, 2492, 2493, 2494, 2495, 2496, 2497, 2498, 2499, 2500, 2501, 2502, 2503, 2504, 2505, 2506, 2507, 2508, 2509, 2510, 2511, 2512, 2513, 2514, 2515, 2516, 2517, 2518, 2519, 2520, 2521, 2522, 2523, 2524, 2525, 2526, 2527, 2528, 2529, 2530, 2531, 2532, 2533, 2534, 2535, 2536, 2537, 2538, 2539, 2540, 2541, 2542, 2543, 2544, 2545, 2546, 2547, 2548, 2549, 2550, 2551, 2552, 2553, 2554, 2555, 2556, 2557, 2558, 2559, 2560, 2561, 2562, 2563, 2564, 2565, 2566, 2567, 2568, 2569, 2570, 2571, 2572, 2573, 2574, 2575, 2576, 2577, 2578, 2579, 2580, 2581, 2582, 2583, 2584, 2585, 2586, 2587, 2588, 2589, 2590, 2591, 2592, 2593, 2594, 2595, 2596, 2597, 2598, 2599, 2600, 2601, 2602, 2603, 2604, 2605, 2606, 2607, 2608, 2609, 2610, 2611, 2612, 2613, 2614, 2615, 2616, 2617, 2618, 2619, 2620, 2621, 2622, 2623, 2624, 2625, 2626, 2627, 2628, 2629, 2630, 2631, 2632, 2633, 2634, 2635, 2636, 2637, 2638, 2639, 2640, 2641, 2642, 2643, 2644, 2645, 2646, 2647, 2648, 2649, 2650, 2651, 2652, 2653, 2654, 2655, 2656, 2657, 2658, 2659, 2660, 2661, 2662, 2663, 2664, 2665, 2666, 2667, 2668, 2669, 2670, 2671, 2672, 2673, 2674, 2675, 2676, 2677, 2678, 2679, 2680, 2681, 2682, 2683, 2684, 2685, 2686, 2687, 2688, 2689, 2690, 2691, 2692, 2693, 2694, 2695, 2696, 2697, 2698, 2699, 2700, 2701, 2702, 2703, 2704, 2705, 2706, 2707, 2708, 2709, 2710, 2711, 2712, 2713, 2714, 2715, 2716, 2717, 2718, 2719, 2720, 2721, 2722, 2723, 2724, 2725, 2726, 2727, 2728, 2729, 2730, 2731, 2732, 2733, 2734, 2735, 2736, 2737, 2738, 2739, 2740, 2741, 2742, 2743, 2744, 2745, 2746, 2747, 2748, 2749, 2750, 2751, 2752, 2753, 2754, 2755, 2756, 2757, 2758, 2759, 2760, 2761, 2762, 2763, 2764, 2765, 2766, 2767, 2768, 2769, 2770, 2771, 2772, 2773, 2774, 2775, 2776, 2777, 2778, 2779, 2780, 2781, 2782, 2783, 2784, 2785, 2786, 2787, 2788, 2789, 2790, 2791, 2792, 2793, 2794, 2795, 2796, 2797, 2798, 2799, 2800, 2801, 2802, 2803, 2804, 2805, 2806, 2807, 2808, 2809, 2810, 2811, 2812, 2813, 2814, 2815, 2816, 2817, 2818, 2819, 2820, 2821, 2822, 2823, 2824, 2825, 2826, 2827, 2828, 2829, 2830, 2831, 2832, 2833, 2834, 2835, 2836, 2837, 2838, 2839, 2840, 2841, 2842, 2843, 2844, 2845, 2846, 2847, 2848, 2849, 2850, 2851, 2852, 2853, 2854, 2855, 2856, 2857, 2858, 2859, 2860, 2861, 2862, 2863, 2864, 2865, 2866, 2867, 2868, 2869, 2870, 2871, 2872, 2873, 2874, 2875, 2876, 2877, 2878, 2879, 2880, 2881, 2882, 2883, 2884, 2885, 2886, 2887, 2888, 2889, 2890, 2891, 2892, 2893, 2894, 2895, 2896, 2897, 2898, 2899, 2900, 2901, 2902, 2903, 2904, 2905, 2906, 2907, 2908, 2909, 2910, 2911, 2912, 2913, 2914, 2915, 2916, 2917, 2918, 2919, 2920, 2921, 2922, 2923, 2924, 2925, 2926, 2927, 2928, 2929, 2930, 2931, 2932, 2933, 2934, 2935, 2936, 2937, 2938, 2939, 2940, 2941, 2942, 2943, 2944, 2945, 2946, 2947, 2948, 2949, 2950, 2951, 2952, 2953, 2954, 2955, 2956, 2957, 2958, 2959, 2960, 2961, 2962, 2963, 2964, 2965, 2966, 2967, 2968, 2969, 2970, 2971, 2972, 2973, 2974, 2975, 2976, 2977, 2978, 2979, 2980, 2981, 2982, 2983, 2984, 2985, 2986, 2987, 2988, 2989, 2990, 2991, 2992, 2993, 2994, 2995, 2996, 2997, 2998, 2999, 3000, 3001, 3002, 3003, 3004, 3005, 3006, 3007, 3008, 3009, 3010, 3011, 3012, 3013, 3014, 3015, 3016, 3017, 3018, 3019, 3020, 3021, 3022, 3023, 3024, 3025, 3026, 3027, 3028, 3029, 3030, 3031, 3032, 3033, 3034, 3035, 3036, 3037, 3038, 3039, 3040, 3041, 3042, 3043, 3044, 3045, 3046, 3047, 3048, 3049, 3050, 3051, 3052, 3053, 3054, 3055, 3056, 3057, 3058, 3059, 3060, 3061, 3062, 3063, 3064, 3065, 3066, 3067, 3068, 3069, 3070, 3071, 3072, 3073, 3074, 3075, 3076, 3077, 3078, 3079, 3080, 3081, 3082, 3083, 3084, 3085, 3086, 3087, 3088, 3089, 3090, 3091, 3092, 3093, 3094, 3095, 3096, 3097, 3098, 3099, 3100, 3101, 3102, 3103, 3104, 3105, 3106, 3107, 3108, 3109, 3110, 3111, 3112, 3113, 3114, 3115, 3116, 3117, 3118, 3119, 3120, 3121, 3122, 3123, 3124, 3125, 3126, 3127, 3128, 3129, 3130, 3131, 3132, 3133, 3134, 3135, 3136, 3137, 3138, 3139, 3140, 3141, 3142, 3143, 3144, 3145, 3146, 3147, 3148, 3149, 3150, 3151, 3152, 3153, 3154, 3155, 3156, 3157, 3158, 3159, 3160, 3161, 3162, 3163, 3164, 3165, 3166, 3167, 3168, 3169, 3170, 3171, 3172, 3173, 3174, 3175, 3176, 3177, 3178, 3179, 3180, 3181, 3182, 3183, 3184, 3185, 3186, 3187, 3188, 3189, 3190, 3191, 3192, 3193, 3194, 3195, 3196, 3197, 3198, 3199, 3200, 3201, 3202, 3203, 3204, 3205, 3206, 3207, 3208, 3209, 3210, 3211, 3212, 3213, 3214, 3215, 3216, 3217, 3218, 3219, 3220, 3221, 3222, 3223, 3224, 3225, 3226, 3227, 3228, 3229, 3230, 3231, 3232, 3233, 3234, 3235, 3236, 3237, 3238, 3239, 3240, 3241, 3242, 3243, 3244, 3245, 3246, 3247, 3248, 3249, 3250, 3251, 3252, 3253, 3254, 3255, 3256, 3257, 3258, 3259, 3260, 3261, 3262, 3263, 3264, 3265, 3266, 3267, 3268, 3269, 3270, 3271, 3272, 3273, 3274, 3275, 3276, 3277, 3278, 3279, 3280, 3281, 3282, 3283, 3284, 3285, 3286, 3287, 3288, 3289, 3290, 3291, 3292, 3293, 3294, 3295, 3296, 3297, 3298, 3299, 3300, 3301, 3302, 3303, 3304, 3305, 3306, 3307, 3308, 3309, 3310, 3311, 3312, 3313, 3314, 3315, 3316, 3317, 3318, 3319, 3320, 3321, 3322, 3323, 3324, 3325, 3326, 3327, 3328, 3329, 3330, 3331, 3332, 3333, 3334, 3335, 3336, 3337, 3338, 3339, 3340, 3341, 3342, 3343, 3344, 3345, 3346, 3347, 3348, 3349, 3350, 3351, 3352, 3353, 3354, 3355, 3356, 3357, 3358, 3359, 3360, 3361, 3362, 3363, 3364, 3365, 3366, 3367, 3368, 3369, 3370, 3371, 3372, 3373, 3374, 3375, 3376, 3377, 3378, 3379, 3380, 3381, 3382, 3383, 3384, 3385, 3386, 3387, 3388, 3389, 3390, 3391, 3392, 3393, 3394, 3395, 3396, 3397, 3398, 3399, 3400, 3401, 3402, 3403, 3404, 3405, 3406, 3407, 3408, 3409, 3410, 3411, 3412, 3413, 3414, 3415, 3416, 3417, 3418, 3419, 3420, 3421, 3422, 3423, 3424, 3425, 3426, 3427, 3428, 3429, 3430, 3431, 3432, 3433, 3434, 3435, 3436, 3437, 3438, 3439, 3440, 3441, 3442, 3443, 3444, 3445, 3446, 3447, 3448, 3449, 3450, 3451, 3452, 3453, 3454, 3455, 3456, 3457, 3458, 3459, 3460, 3461, 3462, 3463, 3464, 3465, 3466, 3467, 3468, 3469, 3470, 3471, 3472, 3473, 3474, 3475, 3476, 3477, 3478, 3479, 3480, 3481, 3482, 3483, 3484, 3485, 3486, 3487, 3488, 3489, 3490, 3491, 3492, 3493, 3494, 3495, 3496, 3497, 3498, 3499, 3500, 3501, 3502, 3503, 3504, 3505, 3506, 3507, 3508, 3509, 3510, 3511, 3512, 3513, 3514, 3515, 3516, 3517, 3518, 3519, 3520, 3521, 3522, 3523, 3524, 3525, 3526, 3527, 3528, 3529, 3530, 3531, 3532, 3533, 3534, 3535, 3536, 3537, 3538, 3539, 3540, 3541, 3542, 3543, 3544, 3545, 3546, 3547, 3548, 3549, 3550, 3551, 3552, 3553, 3554, 3555, 3556, 3557, 3558, 3559, 3560, 3561, 3562, 3563, 3564, 3565, 3566, 3567, 3568, 3569, 3570, 3571, 3572, 3573, 3574, 3575, 3576, 3577, 3578, 3579, 3580, 3581, 3582, 3583, 3584, 3585, 3586, 3587, 3588, 3589, 3590, 3591, 3592, 3593, 3594, 3595, 3596, 3597, 3598, 3599, 3600, 3601, 3602, 3603, 3604, 3605, 3606, 3607, 3608, 3609, 3610, 3611, 3612, 3613, 3614, 3615, 3616, 3617, 3618, 3619, 3620, 3621, 3622, 3623, 3624, 3625, 3626, 3627, 3628, 3629, 3630, 3631, 3632, 3633, 3634, 3635, 3636, 3637, 3638, 3639, 3640, 3641, 3642, 3643, 3644, 3645, 3646, 3647, 3648, 3649, 3650, 3651, 3652, 3653, 3654, 3655, 3656, 3657, 3658, 3659, 3660, 3661, 3662, 3663, 3664, 3665, 3666, 3667, 3668, 3669, 3670, 3671, 3672, 3673, 3674, 3675, 3676, 3677, 3678, 3679, 3680, 3681, 3682, 3683, 3684, 3685, 3686, 3687, 3688, 3689, 3690, 3691, 3692, 3693, 3694, 3695, 3696, 3697, 3698, 3699, 3700, 3701, 3702, 3703, 3704, 3705, 3706, 3707, 3708, 3709, 3710, 3711, 3712, 3713, 3714, 3715, 3716, 3717, 3718, 3719, 3720, 3721, 3722, 3723, 3724, 3725, 3726, 3727, 3728, 3729, 3730, 3731, 3732, 3733, 3734, 3735, 3736, 3737, 3738, 3739, 3740, 3741, 3742, 3743, 3744, 3745, 3746, 3747, 3748, 3749, 3750, 3751, 3752, 3753, 3754, 3755, 3756, 3757, 3758, 3759, 3760, 3761, 3762, 3763, 3764, 3765, 3766, 3767, 3768, 3769, 3770, 3771, 3772, 3773, 3774, 3775, 3776, 3777, 3778, 3779, 3780, 3781, 3782, 3783, 3784, 3785, 3786, 3787, 3788, 3789, 3790, 3791, 3792, 3793, 3794, 3795, 3796, 3797, 3798, 3799, 3800, 3801, 3802, 3803, 3804, 3805, 3806, 3807, 3808, 3809, 3810, 3811, 3812, 3813, 3814, 3815, 3816, 3817, 3818, 3819, 3820, 3821, 3822, 3823, 3824, 3825, 3826, 3827, 3828, 3829, 3830, 3831, 3832, 3833, 3834, 3835, 3836, 3837, 3838, 3839, 3840, 3841, 3842, 3843, 3844, 3845, 3846, 3847, 3848, 3849, 3850, 3851, 3852, 3853, 3854, 3855, 3856, 3857, 3858, 3859, 3860, 3861, 3862, 3863, 3864, 3865, 3866, 3867, 3868, 3869, 3870, 3871, 3872, 3873, 3874, 3875, 3876, 3877, 3878, 3879, 3880, 3881, 3882, 3883, 3884, 3885, 3886, 3887, 3888, 3889, 3890, 3891, 3892, 3893, 3894, 3895, 3896, 3897, 3898, 3899, 3900, 3901, 3902, 3903, 3904, 3905, 3906, 3907, 3908, 3909, 3910, 3911, 3912, 3913, 3914, 3915, 3916, 3917, 3918, 3919, 3920, 3921, 3922, 3923, 3924, 3925, 3926, 3927, 3928, 3929, 3930, 3931, 3932, 3933, 3934, 3935, 3936, 3937, 3938, 3939, 3940, 3941, 3942, 3943, 3944, 3945, 3946, 3947, 3948, 3949, 3950, 3951, 3952, 3953, 3954, 3955, 3956, 3957, 3958, 3959, 3960, 3961, 3962, 3963, 3964, 3965, 3966, 3967, 3968, 3969, 3970, 3971, 3972, 3973, 3974, 3975, 3976, 3977, 3978, 3979, 3980, 3981, 3982, 3983, 3984, 3985, 3986, 3987, 3988, 3989, 3990, 3991, 3992, 3993, 3994, 3995, 3996, 3997, 3998, 3999, 4000, 4001, 4002, 4003, 4004, 4005, 4006, 4007, 4008, 4009, 4010, 4011, 4012, 4013, 4014, 4015, 4016, 4017, 4018, 4019, 4020, 4021, 4022, 4023, 4024, 4025, 4026, 4027, 4028, 4029, 4030, 4031, 4032, 4033, 4034, 4035, 4036, 4037, 4038, 4039, 4040, 4041, 4042, 4043, 4044, 4045, 4046, 4047, 4048, 4049, 4050, 4051, 4052, 4053, 4054, 4055, 4056, 4057, 4058, 4059, 4060, 4061, 4062, 4063, 4064, 4065, 4066, 4067, 4068, 4069, 4070, 4071, 4072, 4073, 4074, 4075, 4076, 4077, 4078, 4079, 4080, 4081, 4082, 4083, 4084, 4085, 4086, 4087, 4088, 4089, 4090, 4091, 4092, 4093, 4094, 4095, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 256, 257, 258, 259, 260, 261, 262, 263, 264, 265, 266, 267, 268, 269, 270, 271, 272, 273, 274, 275, 276, 277, 278, 279, 280, 281, 282, 283, 284, 285, 286, 287, 288, 289, 290, 291, 292, 293, 294, 295, 296, 297, 298, 299, 300, 301, 302, 303, 304, 305, 306, 307, 308, 309, 310, 311, 312, 313, 314, 315, 316, 317, 318, 319, 320, 321, 322, 323, 324, 325, 326, 327, 328, 329, 330, 331, 332, 333, 334, 335, 336, 337, 338, 339, 340, 341, 342, 343, 344, 345, 346, 347, 348, 349, 350, 351, 352, 353, 354, 355, 356, 357, 358, 359, 360, 361, 362, 363, 364, 365, 366, 367, 368, 369, 370, 371, 372, 373, 374, 375, 376, 377, 378, 379, 380, 381, 382, 383, 384, 385, 386, 387, 388, 389, 390, 391, 392, 393, 394, 395, 396, 397, 398, 399, 400, 401, 402, 403, 404, 405, 406, 407, 408, 409, 410, 411, 412, 413, 414, 415, 416, 417, 418, 419, 420, 421, 422, 423, 424, 425, 426, 427, 428, 429, 430, 431, 432, 433, 434, 435, 436, 437, 438, 439, 440, 441, 442, 443, 444, 445, 446, 447, 448, 449, 450, 451, 452, 453, 454, 455, 456, 457, 458, 459, 460, 461, 462, 463, 464, 465, 466, 467, 468, 469, 470, 471, 472, 473, 474, 475, 476, 477, 478, 479, 480, 481, 482, 483, 484, 485, 486, 487, 488, 489, 490, 491, 492, 493, 494, 495, 496, 497, 498, 499, 500, 501, 502, 503, 504, 505, 506, 507, 508, 509, 510, 511, 512, 513, 514, 515, 516, 517, 518, 519, 520, 521, 522, 523, 524, 525, 526, 527, 528, 529, 530, 531, 532, 533, 534, 535, 536, 537, 538, 539, 540, 541, 542, 543, 544, 545, 546, 547, 548, 549, 550, 551, 552, 553, 554, 555, 556, 557, 558, 559, 560, 561, 562, 563, 564, 565, 566, 567, 568, 569, 570, 571, 572, 573, 574, 575, 576, 577, 578, 579, 580, 581, 582, 583, 584, 585, 586, 587, 588, 589, 590, 591, 592, 593, 594, 595, 596, 597, 598, 599, 600, 601, 602, 603, 604, 605, 606, 607, 608, 609, 610, 611, 612, 613, 614, 615, 616, 617, 618, 619, 620, 621, 622, 623, 624, 625, 626, 627, 628, 629, 630, 631, 632, 633, 634, 635, 636, 637, 638, 639, 640, 641, 642, 643, 644, 645, 646, 647, 648, 649, 650, 651, 652, 653, 654, 655, 656, 657, 658, 659, 660, 661, 662, 663, 664, 665, 666, 667, 668, 669, 670, 671, 672, 673, 674, 675, 676, 677, 678, 679, 680, 681, 682, 683, 684, 685, 686, 687, 688, 689, 690, 691, 692, 693, 694, 695, 696, 697, 698, 699, 700, 701, 702, 703, 704, 705, 706, 707, 708, 709, 710, 711, 712, 713, 714, 715, 716, 717, 718, 719, 720, 721, 722, 723, 724, 725, 726, 727, 728, 729, 730, 731, 732, 733, 734, 735, 736, 737, 738, 739, 740, 741, 742, 743, 744, 745, 746, 747, 748, 749, 750, 751, 752, 753, 754, 755, 756, 757, 758, 759, 760, 761, 762, 763, 764, 765, 766, 767, 768, 769, 770, 771, 772, 773, 774, 775, 776, 777, 778, 779, 780, 781, 782, 783, 784, 785, 786, 787, 788, 789, 790, 791, 792, 793, 794, 795, 796, 797, 798, 799, 800, 801, 802, 803, 804, 805, 806, 807, 808, 809, 810, 811, 812, 813, 814, 815, 816, 817, 818, 819, 820, 821, 822, 823, 824, 825, 826, 827, 828, 829, 830, 831, 832, 833, 834, 835, 836, 837, 838, 839, 840, 841, 842, 843, 844, 845, 846, 847, 848, 849, 850, 851, 852, 853, 854, 855, 856, 857, 858, 859, 860, 861, 862, 863, 864, 865, 866, 867, 868, 869, 870, 871, 872, 873, 874, 875, 876, 877, 878, 879, 880, 881, 882, 883, 884, 885, 886, 887, 888, 889, 890, 891, 892, 893, 894, 895, 896, 897, 898, 899, 900, 901, 902, 903, 904, 905, 906, 907, 908, 909, 910, 911, 912, 913, 914, 915, 916, 917, 918, 919, 920, 921, 922, 923, 924, 925, 926, 927, 928, 929, 930, 931, 932, 933, 934, 935, 936, 937, 938, 939, 940, 941, 942, 943, 944, 945, 946, 947, 948, 949, 950, 951, 952, 953, 954, 955, 956, 957, 958, 959, 960, 961, 962, 963, 964, 965, 966, 967, 968, 969, 970, 971, 972, 973, 974, 975, 976, 977, 978, 979, 980, 981, 982, 983, 984, 985, 986, 987, 988, 989, 990, 991, 992, 993, 994, 995, 996, 997, 998, 999, 1000, 1001, 1002, 1003, 1004, 1005, 1006, 1007, 1008, 1009, 1010, 1011, 1012, 1013, 1014, 1015, 1016, 1017, 1018, 1019, 1020, 1021, 1022, 1023, 1024, 1025, 1026, 1027, 1028, 1029, 1030, 1031, 1032, 1033, 1034, 1035, 1036, 1037, 1038, 1039, 1040, 1041, 1042, 1043, 1044, 1045, 1046, 1047, 1048, 1049, 1050, 1051, 1052, 1053, 1054, 1055, 1056, 1057, 1058, 1059, 1060, 1061, 1062, 1063, 1064, 1065, 1066, 1067, 1068, 1069, 1070, 1071, 1072, 1073, 1074, 1075, 1076, 1077, 1078, 1079, 1080, 1081, 1082, 1083, 1084, 1085, 1086, 1087, 1088, 1089, 1090, 1091, 1092, 1093, 1094, 1095, 1096, 1097, 1098, 1099, 1100, 1101, 1102, 1103, 1104, 1105, 1106, 1107, 1108, 1109, 1110, 1111, 1112, 1113, 1114, 1115, 1116, 1117, 1118, 1119, 1120, 1121, 1122, 1123, 1124, 1125, 1126, 1127, 1128, 1129, 1130, 1131, 1132, 1133, 1134, 1135, 1136, 1137, 1138, 1139, 1140, 1141, 1142, 1143, 1144, 1145, 1146, 1147, 1148, 1149, 1150, 1151, 1152, 1153, 1154, 1155, 1156, 1157, 1158, 1159, 1160, 1161, 1162, 1163, 1164, 1165, 1166, 1167, 1168, 1169, 1170, 1171, 1172, 1173, 1174, 1175, 1176, 1177, 1178, 1179, 1180, 1181, 1182, 1183, 1184, 1185, 1186, 1187, 1188, 1189, 1190, 1191, 1192, 1193, 1194, 1195, 1196, 1197, 1198, 1199, 1200, 1201, 1202, 1203, 1204, 1205, 1206, 1207, 1208, 1209, 1210, 1211, 1212, 1213, 1214, 1215, 1216, 1217, 1218, 1219, 1220, 1221, 1222, 1223, 1224, 1225, 1226, 1227, 1228, 1229, 1230, 1231, 1232, 1233, 1234, 1235, 1236, 1237, 1238, 1239, 1240, 1241, 1242, 1243, 1244, 1245, 1246, 1247, 1248, 1249, 1250, 1251, 1252, 1253, 1254, 1255, 1256, 1257, 1258, 1259, 1260, 1261, 1262, 1263, 1264, 1265, 1266, 1267, 1268, 1269, 1270, 1271, 1272, 1273, 1274, 1275, 1276, 1277, 1278, 1279, 1280, 1281, 1282, 1283, 1284, 1285, 1286, 1287, 1288, 1289, 1290, 1291, 1292, 1293, 1294, 1295, 1296, 1297, 1298, 1299, 1300, 1301, 1302, 1303, 1304, 1305, 1306, 1307, 1308, 1309, 1310, 1311, 1312, 1313, 1314, 1315, 1316, 1317, 1318, 1319, 1320, 1321, 1322, 1323, 1324, 1325, 1326, 1327, 1328, 1329, 1330, 1331, 1332, 1333, 1334, 1335, 1336, 1337, 1338, 1339, 1340, 1341, 1342, 1343, 1344, 1345, 1346, 1347, 1348, 1349, 1350, 1351, 1352, 1353, 1354, 1355, 1356, 1357, 1358, 1359, 1360, 1361, 1362, 1363, 1364, 1365, 1366, 1367, 1368, 1369, 1370, 1371, 1372, 1373, 1374, 1375, 1376, 1377, 1378, 1379, 1380, 1381, 1382, 1383, 1384, 1385, 1386, 1387, 1388, 1389, 1390, 1391, 1392, 1393, 1394, 1395, 1396, 1397, 1398, 1399, 1400, 1401, 1402, 1403, 1404, 1405, 1406, 1407, 1408, 1409, 1410, 1411, 1412, 1413, 1414, 1415, 1416, 1417, 1418, 1419, 1420, 1421, 1422, 1423, 1424, 1425, 1426, 1427, 1428, 1429, 1430, 1431, 1432, 1433, 1434, 1435, 1436, 1437, 1438, 1439, 1440, 1441, 1442, 1443, 1444, 1445, 1446, 1447, 1448, 1449, 1450, 1451, 1452, 1453, 1454, 1455, 1456, 1457, 1458, 1459, 1460, 1461, 1462, 1463, 1464, 1465, 1466, 1467, 1468, 1469, 1470, 1471, 1472, 1473, 1474, 1475, 1476, 1477, 1478, 1479, 1480, 1481, 1482, 1483, 1484, 1485, 1486, 1487, 1488, 1489, 1490, 1491, 1492, 1493, 1494, 1495, 1496, 1497, 1498, 1499, 1500, 1501, 1502, 1503, 1504, 1505, 1506, 1507, 1508, 1509, 1510, 1511, 1512, 1513, 1514, 1515, 1516, 1517, 1518, 1519, 1520, 1521, 1522, 1523, 1524, 1525, 1526, 1527, 1528, 1529, 1530, 1531, 1532, 1533, 1534, 1535, 1536, 1537, 1538, 1539, 1540, 1541, 1542, 1543, 1544, 1545, 1546, 1547, 1548, 1549, 1550, 1551, 1552, 1553, 1554, 1555, 1556, 1557, 1558, 1559, 1560, 1561, 1562, 1563, 1564, 1565, 1566, 1567, 1568, 1569, 1570, 1571, 1572, 1573, 1574, 1575, 1576, 1577, 1578, 1579, 1580, 1581, 1582, 1583, 1584, 1585, 1586, 1587, 1588, 1589, 1590, 1591, 1592, 1593, 1594, 1595, 1596, 1597, 1598, 1599, 1600, 1601, 1602, 1603, 1604, 1605, 1606, 1607, 1608, 1609, 1610, 1611, 1612, 1613, 1614, 1615, 1616, 1617, 1618, 1619, 1620, 1621, 1622, 1623, 1624, 1625, 1626, 1627, 1628, 1629, 1630, 1631, 1632, 1633, 1634, 1635, 1636, 1637, 1638, 1639, 1640, 1641, 1642, 1643, 1644, 1645, 1646, 1647, 1648, 1649, 1650, 1651, 1652, 1653, 1654, 1655, 1656, 1657, 1658, 1659, 1660, 1661, 1662, 1663, 1664, 1665, 1666, 1667, 1668, 1669, 1670, 1671, 1672, 1673, 1674, 1675, 1676, 1677, 1678, 1679, 1680, 1681, 1682, 1683, 1684, 1685, 1686, 1687, 1688, 1689, 1690, 1691, 1692, 1693, 1694, 1695, 1696, 1697, 1698, 1699, 1700, 1701, 1702, 1703, 1704, 1705, 1706, 1707, 1708, 1709, 1710, 1711, 1712, 1713, 1714, 1715, 1716, 1717, 1718, 1719, 1720, 1721, 1722, 1723, 1724, 1725, 1726, 1727, 1728, 1729, 1730, 1731, 1732, 1733, 1734, 1735, 1736, 1737, 1738, 1739, 1740, 1741, 1742, 1743, 1744, 1745, 1746, 1747, 1748, 1749, 1750, 1751, 1752, 1753, 1754, 1755, 1756, 1757, 1758, 1759, 1760, 1761, 1762, 1763, 1764, 1765, 1766, 1767, 1768, 1769, 1770, 1771, 1772, 1773, 1774, 1775, 1776, 1777, 1778, 1779, 1780, 1781, 1782, 1783, 1784, 1785, 1786, 1787, 1788, 1789, 1790, 1791, 1792, 1793, 1794, 1795, 1796, 1797, 1798, 1799, 1800, 1801, 1802, 1803, 1804, 1805, 1806, 1807, 1808, 1809, 1810, 1811, 1812, 1813, 1814, 1815, 1816, 1817, 1818, 1819, 1820, 1821, 1822, 1823, 1824, 1825, 1826, 1827, 1828, 1829, 1830, 1831, 1832, 1833, 1834, 1835, 1836, 1837, 1838, 1839, 1840, 1841, 1842, 1843, 1844, 1845, 1846, 1847, 1848, 1849, 1850, 1851, 1852, 1853, 1854, 1855, 1856, 1857, 1858, 1859, 1860, 1861, 1862, 1863, 1864, 1865, 1866, 1867, 1868, 1869, 1870, 1871, 1872, 1873, 1874, 1875, 1876, 1877, 1878, 1879, 1880, 1881, 1882, 1883, 1884, 1885, 1886, 1887, 1888, 1889, 1890, 1891, 1892, 1893, 1894, 1895, 1896, 1897, 1898, 1899, 1900, 1901, 1902, 1903, 1904, 1905, 1906, 1907, 1908, 1909, 1910, 1911, 1912, 1913, 1914, 1915, 1916, 1917, 1918, 1919, 1920, 1921, 1922, 1923, 1924, 1925, 1926, 1927, 1928, 1929, 1930, 1931, 1932, 1933, 1934, 1935, 1936, 1937, 1938, 1939, 1940, 1941, 1942, 1943, 1944, 1945, 1946, 1947, 1948, 1949, 1950, 1951, 1952, 1953, 1954, 1955, 1956, 1957, 1958, 1959, 1960, 1961, 1962, 1963, 1964, 1965, 1966, 1967, 1968, 1969, 1970, 1971, 1972, 1973, 1974, 1975, 1976, 1977, 1978, 1979, 1980, 1981, 1982, 1983, 1984, 1985, 1986, 1987, 1988, 1989, 1990, 1991, 1992, 1993, 1994, 1995, 1996, 1997, 1998, 1999, 2000, 2001, 2002, 2003, 2004, 2005, 2006, 2007, 2008, 2009, 2010, 2011, 2012, 2013, 2014, 2015, 2016, 2017, 2018, 2019, 2020, 2021, 2022, 2023, 2024, 2025, 2026, 2027, 2028, 2029, 2030, 2031, 2032, 2033, 2034, 2035, 2036, 2037, 2038, 2039, 2040, 2041, 2042, 2043, 2044, 2045, 2046, 2047, 2048, 2049, 2050, 2051, 2052, 2053, 2054, 2055, 2056, 2057, 2058, 2059, 2060, 2061, 2062, 2063, 2064, 2065, 2066, 2067, 2068, 2069, 2070, 2071, 2072, 2073, 2074, 2075, 2076, 2077, 2078, 2079, 2080, 2081, 2082, 2083, 2084, 2085, 2086, 2087, 2088, 2089, 2090, 2091, 2092, 2093, 2094, 2095, 2096, 2097, 2098, 2099, 2100, 2101, 2102, 2103, 2104, 2105, 2106, 2107, 2108, 2109, 2110, 2111, 2112, 2113, 2114, 2115, 2116, 2117, 2118, 2119, 2120, 2121, 2122, 2123, 2124, 2125, 2126, 2127, 2128, 2129, 2130, 2131, 2132, 2133, 2134, 2135, 2136, 2137, 2138, 2139, 2140, 2141, 2142, 2143, 2144, 2145, 2146, 2147, 2148, 2149, 2150, 2151, 2152, 2153, 2154, 2155, 2156, 2157, 2158, 2159, 2160, 2161, 2162, 2163, 2164, 2165, 2166, 2167, 2168, 2169, 2170, 2171, 2172, 2173, 2174, 2175, 2176, 2177, 2178, 2179, 2180, 2181, 2182, 2183, 2184, 2185, 2186, 2187, 2188, 2189, 2190, 2191, 2192, 2193, 2194, 2195, 2196, 2197, 2198, 2199, 2200, 2201, 2202, 2203, 2204, 2205, 2206, 2207, 2208, 2209, 2210, 2211, 2212, 2213, 2214, 2215, 2216, 2217, 2218, 2219, 2220, 2221, 2222, 2223, 2224, 2225, 2226, 2227, 2228, 2229, 2230, 2231, 2232, 2233, 2234, 2235, 2236, 2237, 2238, 2239, 2240, 2241, 2242, 2243, 2244, 2245, 2246, 2247, 2248, 2249, 2250, 2251, 2252, 2253, 2254, 2255, 2256, 2257, 2258, 2259, 2260, 2261, 2262, 2263, 2264, 2265, 2266, 2267, 2268, 2269, 2270, 2271, 2272, 2273, 2274, 2275, 2276, 2277, 2278, 2279, 2280, 2281, 2282, 2283, 2284, 2285, 2286, 2287, 2288, 2289, 2290, 2291, 2292, 2293, 2294, 2295, 2296, 2297, 2298, 2299, 2300, 2301, 2302, 2303, 2304, 2305, 2306, 2307, 2308, 2309, 2310, 2311, 2312, 2313, 2314, 2315, 2316, 2317, 2318, 2319, 2320, 2321, 2322, 2323, 2324, 2325, 2326, 2327, 2328, 2329, 2330, 2331, 2332, 2333, 2334, 2335, 2336, 2337, 2338, 2339, 2340, 2341, 2342, 2343, 2344, 2345, 2346, 2347, 2348, 2349, 2350, 2351, 2352, 2353, 2354, 2355, 2356, 2357, 2358, 2359, 2360, 2361, 2362, 2363, 2364, 2365, 2366, 2367, 2368, 2369, 2370, 2371, 2372, 2373, 2374, 2375, 2376, 2377, 2378, 2379, 2380, 2381, 2382, 2383, 2384, 2385, 2386, 2387, 2388, 2389, 2390, 2391, 2392, 2393, 2394, 2395, 2396, 2397, 2398, 2399, 2400, 2401, 2402, 2403, 2404, 2405, 2406, 2407, 2408, 2409, 2410, 2411, 2412, 2413, 2414, 2415, 2416, 2417, 2418, 2419, 2420, 2421, 2422, 2423, 2424, 2425, 2426, 2427, 2428, 2429, 2430, 2431, 2432, 2433, 2434, 2435, 2436, 2437, 2438, 2439, 2440, 2441, 2442, 2443, 2444, 2445, 2446, 2447, 2448, 2449, 2450, 2451, 2452, 2453, 2454, 2455, 2456, 2457, 2458, 2459, 2460, 2461, 2462, 2463, 2464, 2465, 2466, 2467, 2468, 2469, 2470, 2471, 2472, 2473, 2474, 2475, 2476, 2477, 2478, 2479, 2480, 2481, 2482, 2483, 2484, 2485, 2486, 2487, 2488, 2489, 2490, 2491, 2492, 2493, 2494, 2495, 2496, 2497, 2498, 2499, 2500, 2501, 2502, 2503, 2504, 2505, 2506, 2507, 2508, 2509, 2510, 2511, 2512, 2513, 2514, 2515, 2516, 2517, 2518, 2519, 2520, 2521, 2522, 2523, 2524, 2525, 2526, 2527, 2528, 2529, 2530, 2531, 2532, 2533, 2534, 2535, 2536, 2537, 2538, 2539, 2540, 2541, 2542, 2543, 2544, 2545, 2546, 2547, 2548, 2549, 2550, 2551, 2552, 2553, 2554, 2555, 2556, 2557, 2558, 2559, 2560, 2561, 2562, 2563, 2564, 2565, 2566, 2567, 2568, 2569, 2570, 2571, 2572, 2573, 2574, 2575, 2576, 2577, 2578, 2579, 2580, 2581, 2582, 2583, 2584, 2585, 2586, 2587, 2588, 2589, 2590, 2591, 2592, 2593, 2594, 2595, 2596, 2597, 2598, 2599, 2600, 2601, 2602, 2603, 2604, 2605, 2606, 2607, 2608, 2609, 2610, 2611, 2612, 2613, 2614, 2615, 2616, 2617, 2618, 2619, 2620, 2621, 2622, 2623, 2624, 2625, 2626, 2627, 2628, 2629, 2630, 2631, 2632, 2633, 2634, 2635, 2636, 2637, 2638, 2639, 2640, 2641, 2642, 2643, 2644, 2645, 2646, 2647, 2648, 2649, 2650, 2651, 2652, 2653, 2654, 2655, 2656, 2657, 2658, 2659, 2660, 2661, 2662, 2663, 2664, 2665, 2666, 2667, 2668, 2669, 2670, 2671, 2672, 2673, 2674, 2675, 2676, 2677, 2678, 2679, 2680, 2681, 2682, 2683, 2684, 2685, 2686, 2687, 2688, 2689, 2690, 2691, 2692, 2693, 2694, 2695, 2696, 2697, 2698, 2699, 2700, 2701, 2702, 2703, 2704, 2705, 2706, 2707, 2708, 2709, 2710, 2711, 2712, 2713, 2714, 2715, 2716, 2717, 2718, 2719, 2720, 2721, 2722, 2723, 2724, 2725, 2726, 2727, 2728, 2729, 2730, 2731, 2732, 2733, 2734, 2735, 2736, 2737, 2738, 2739, 2740, 2741, 2742, 2743, 2744, 2745, 2746, 2747, 2748, 2749, 2750, 2751, 2752, 2753, 2754, 2755, 2756, 2757, 2758, 2759, 2760, 2761, 2762, 2763, 2764, 2765, 2766, 2767, 2768, 2769, 2770, 2771, 2772, 2773, 2774, 2775, 2776, 2777, 2778, 2779, 2780, 2781, 2782, 2783, 2784, 2785, 2786, 2787, 2788, 2789, 2790, 2791, 2792, 2793, 2794, 2795, 2796, 2797, 2798, 2799, 2800, 2801, 2802, 2803, 2804, 2805, 2806, 2807, 2808, 2809, 2810, 2811, 2812, 2813, 2814, 2815, 2816, 2817, 2818, 2819, 2820, 2821, 2822, 2823, 2824, 2825, 2826, 2827, 2828, 2829, 2830, 2831, 2832, 2833, 2834, 2835, 2836, 2837, 2838, 2839, 2840, 2841, 2842, 2843, 2844, 2845, 2846, 2847, 2848, 2849, 2850, 2851, 2852, 2853, 2854, 2855, 2856, 2857, 2858, 2859, 2860, 2861, 2862, 2863, 2864, 2865, 2866, 2867, 2868, 2869, 2870, 2871, 2872, 2873, 2874, 2875, 2876, 2877, 2878, 2879, 2880, 2881, 2882, 2883, 2884, 2885, 2886, 2887, 2888, 2889, 2890, 2891, 2892, 2893, 2894, 2895, 2896, 2897, 2898, 2899, 2900, 2901, 2902, 2903, 2904, 2905, 2906, 2907, 2908, 2909, 2910, 2911, 2912, 2913, 2914, 2915, 2916, 2917, 2918, 2919, 2920, 2921, 2922, 2923, 2924, 2925, 2926, 2927, 2928, 2929, 2930, 2931, 2932, 2933, 2934, 2935, 2936, 2937, 2938, 2939, 2940, 2941, 2942, 2943, 2944, 2945, 2946, 2947, 2948, 2949, 2950, 2951, 2952, 2953, 2954, 2955, 2956, 2957, 2958, 2959, 2960, 2961, 2962, 2963, 2964, 2965, 2966, 2967, 2968, 2969, 2970, 2971, 2972, 2973, 2974, 2975, 2976, 2977, 2978, 2979, 2980, 2981, 2982, 2983, 2984, 2985, 2986, 2987, 2988, 2989, 2990, 2991, 2992, 2993, 2994, 2995, 2996, 2997, 2998, 2999, 3000, 3001, 3002, 3003, 3004, 3005, 3006, 3007, 3008, 3009, 3010, 3011, 3012, 3013, 3014, 3015, 3016, 3017, 3018, 3019, 3020, 3021, 3022, 3023, 3024, 3025, 3026, 3027, 3028, 3029, 3030, 3031, 3032, 3033, 3034, 3035, 3036, 3037, 3038, 3039, 3040, 3041, 3042, 3043, 3044, 3045, 3046, 3047, 3048, 3049, 3050, 3051, 3052, 3053, 3054, 3055, 3056, 3057, 3058, 3059, 3060, 3061, 3062, 3063, 3064, 3065, 3066, 3067, 3068, 3069, 3070, 3071, 3072, 3073, 3074, 3075, 3076, 3077, 3078, 3079, 3080, 3081, 3082, 3083, 3084, 3085, 3086, 3087, 3088, 3089, 3090, 3091, 3092, 3093, 3094, 3095, 3096, 3097, 3098, 3099, 3100, 3101, 3102, 3103, 3104, 3105, 3106, 3107, 3108, 3109, 3110, 3111, 3112, 3113, 3114, 3115, 3116, 3117, 3118, 3119, 3120, 3121, 3122, 3123, 3124, 3125, 3126, 3127, 3128, 3129, 3130, 3131, 3132, 3133, 3134, 3135, 3136, 3137, 3138, 3139, 3140, 3141, 3142, 3143, 3144, 3145, 3146, 3147, 3148, 3149, 3150, 3151, 3152, 3153, 3154, 3155, 3156, 3157, 3158, 3159, 3160, 3161, 3162, 3163, 3164, 3165, 3166, 3167, 3168, 3169, 3170, 3171, 3172, 3173, 3174, 3175, 3176, 3177, 3178, 3179, 3180, 3181, 3182, 3183, 3184, 3185, 3186, 3187, 3188, 3189, 3190, 3191, 3192, 3193, 3194, 3195, 3196, 3197, 3198, 3199, 3200, 3201, 3202, 3203, 3204, 3205, 3206, 3207, 3208, 3209, 3210, 3211, 3212, 3213, 3214, 3215, 3216, 3217, 3218, 3219, 3220, 3221, 3222, 3223, 3224, 3225, 3226, 3227, 3228, 3229, 3230, 3231, 3232, 3233, 3234, 3235, 3236, 3237, 3238, 3239, 3240, 3241, 3242, 3243, 3244, 3245, 3246, 3247, 3248, 3249, 3250, 3251, 3252, 3253, 3254, 3255, 3256, 3257, 3258, 3259, 3260, 3261, 3262, 3263, 3264, 3265, 3266, 3267, 3268, 3269, 3270, 3271, 3272, 3273, 3274, 3275, 3276, 3277, 3278, 3279, 3280, 3281, 3282, 3283, 3284, 3285, 3286, 3287, 3288, 3289, 3290, 3291, 3292, 3293, 3294, 3295, 3296, 3297, 3298, 3299, 3300, 3301, 3302, 3303, 3304, 3305, 3306, 3307, 3308, 3309, 3310, 3311, 3312, 3313, 3314, 3315, 3316, 3317, 3318, 3319, 3320, 3321, 3322, 3323, 3324, 3325, 3326, 3327, 3328, 3329, 3330, 3331, 3332, 3333, 3334, 3335, 3336, 3337, 3338, 3339, 3340, 3341, 3342, 3343, 3344, 3345, 3346, 3347, 3348, 3349, 3350, 3351, 3352, 3353, 3354, 3355, 3356, 3357, 3358, 3359, 3360, 3361, 3362, 3363, 3364, 3365, 3366, 3367, 3368, 3369, 3370, 3371, 3372, 3373, 3374, 3375, 3376, 3377, 3378, 3379, 3380, 3381, 3382, 3383, 3384, 3385, 3386, 3387, 3388, 3389, 3390, 3391, 3392, 3393, 3394, 3395, 3396, 3397, 3398, 3399, 3400, 3401, 3402, 3403, 3404, 3405, 3406, 3407, 3408, 3409, 3410, 3411, 3412, 3413, 3414, 3415, 3416, 3417, 3418, 3419, 3420, 3421, 3422, 3423, 3424, 3425, 3426, 3427, 3428, 3429, 3430, 3431, 3432, 3433, 3434, 3435, 3436, 3437, 3438, 3439, 3440, 3441, 3442, 3443, 3444, 3445, 3446, 3447, 3448, 3449, 3450, 3451, 3452, 3453, 3454, 3455, 3456, 3457, 3458, 3459, 3460, 3461, 3462, 3463, 3464, 3465, 3466, 3467, 3468, 3469, 3470, 3471, 3472, 3473, 3474, 3475, 3476, 3477, 3478, 3479, 3480, 3481, 3482, 3483, 3484, 3485, 3486, 3487, 3488, 3489, 3490, 3491, 3492, 3493, 3494, 3495, 3496, 3497, 3498, 3499, 3500, 3501, 3502, 3503, 3504, 3505, 3506, 3507, 3508, 3509, 3510, 3511, 3512, 3513, 3514, 3515, 3516, 3517, 3518, 3519, 3520, 3521, 3522, 3523, 3524, 3525, 3526, 3527, 3528, 3529, 3530, 3531, 3532, 3533, 3534, 3535, 3536, 3537, 3538, 3539, 3540, 3541, 3542, 3543, 3544, 3545, 3546, 3547, 3548, 3549, 3550, 3551, 3552, 3553, 3554, 3555, 3556, 3557, 3558, 3559, 3560, 3561, 3562, 3563, 3564, 3565, 3566, 3567, 3568, 3569, 3570, 3571, 3572, 3573, 3574, 3575, 3576, 3577, 3578, 3579, 3580, 3581, 3582, 3583, 3584, 3585, 3586, 3587, 3588, 3589, 3590, 3591, 3592, 3593, 3594, 3595, 3596, 3597, 3598, 3599, 3600, 3601, 3602, 3603, 3604, 3605, 3606, 3607, 3608, 3609, 3610, 3611, 3612, 3613, 3614, 3615, 3616, 3617, 3618, 3619, 3620, 3621, 3622, 3623, 3624, 3625, 3626, 3627, 3628, 3629, 3630, 3631, 3632, 3633, 3634, 3635, 3636, 3637, 3638, 3639, 3640, 3641, 3642, 3643, 3644, 3645, 3646, 3647, 3648, 3649, 3650, 3651, 3652, 3653, 3654, 3655, 3656, 3657, 3658, 3659, 3660, 3661, 3662, 3663, 3664, 3665, 3666, 3667, 3668, 3669, 3670, 3671, 3672, 3673, 3674, 3675, 3676, 3677, 3678, 3679, 3680, 3681, 3682, 3683, 3684, 3685, 3686, 3687, 3688, 3689, 3690, 3691, 3692, 3693, 3694, 3695, 3696, 3697, 3698, 3699, 3700, 3701, 3702, 3703, 3704, 3705, 3706, 3707, 3708, 3709, 3710, 3711, 3712, 3713, 3714, 3715, 3716, 3717, 3718, 3719, 3720, 3721, 3722, 3723, 3724, 3725, 3726, 3727, 3728, 3729, 3730, 3731, 3732, 3733, 3734, 3735, 3736, 3737, 3738, 3739, 3740, 3741, 3742, 3743, 3744, 3745, 3746, 3747, 3748, 3749, 3750, 3751, 3752, 3753, 3754, 3755, 3756, 3757, 3758, 3759, 3760, 3761, 3762, 3763, 3764, 3765, 3766, 3767, 3768, 3769, 3770, 3771, 3772, 3773, 3774, 3775, 3776, 3777, 3778, 3779, 3780, 3781, 3782, 3783, 3784, 3785, 3786, 3787, 3788, 3789, 3790, 3791, 3792, 3793, 3794, 3795, 3796, 3797, 3798, 3799, 3800, 3801, 3802, 3803, 3804, 3805, 3806, 3807, 3808, 3809, 3810, 3811, 3812, 3813, 3814, 3815, 3816, 3817, 3818, 3819, 3820, 3821, 3822, 3823, 3824, 3825, 3826, 3827, 3828, 3829, 3830, 3831, 3832, 3833, 3834, 3835, 3836, 3837, 3838, 3839, 3840, 3841, 3842, 3843, 3844, 3845, 3846, 3847, 3848, 3849, 3850, 3851, 3852, 3853, 3854, 3855, 3856, 3857, 3858, 3859, 3860, 3861, 3862, 3863, 3864, 3865, 3866, 3867, 3868, 3869, 3870, 3871, 3872, 3873, 3874, 3875, 3876, 3877, 3878, 3879, 3880, 3881, 3882, 3883, 3884, 3885, 3886, 3887, 3888, 3889, 3890, 3891, 3892, 3893, 3894, 3895, 3896, 3897, 3898, 3899, 3900, 3901, 3902, 3903, 3904, 3905, 3906, 3907, 3908, 3909, 3910, 3911, 3912, 3913, 3914, 3915, 3916, 3917, 3918, 3919, 3920, 3921, 3922, 3923, 3924, 3925, 3926, 3927, 3928, 3929, 3930, 3931, 3932, 3933, 3934, 3935, 3936, 3937, 3938, 3939, 3940, 3941, 3942, 3943, 3944, 3945, 3946, 3947, 3948, 3949, 3950, 3951, 3952, 3953, 3954, 3955, 3956, 3957, 3958, 3959, 3960, 3961, 3962, 3963, 3964, 3965, 3966, 3967, 3968, 3969, 3970, 3971, 3972, 3973, 3974, 3975, 3976, 3977, 3978, 3979, 3980, 3981, 3982, 3983, 3984, 3985, 3986, 3987, 3988, 3989, 3990, 3991, 3992, 3993, 3994, 3995, 3996, 3997, 3998, 3999, 4000, 4001, 4002, 4003, 4004, 4005, 4006, 4007, 4008, 4009, 4010, 4011, 4012, 4013, 4014, 4015, 4016, 4017, 4018, 4019, 4020, 4021, 4022, 4023, 4024, 4025, 4026, 4027, 4028, 4029, 4030, 4031, 4032, 4033, 4034, 4035, 4036, 4037, 4038, 4039, 4040, 4041, 4042, 4043, 4044, 4045, 4046, 4047, 4048, 4049, 4050, 4051, 4052, 4053, 4054, 4055, 4056, 4057, 4058, 4059, 4060, 4061, 4062, 4063, 4064, 4065, 4066, 4067, 4068, 4069, 4070, 4071, 4072, 4073, 4074, 4075, 4076, 4077, 4078, 4079, 4080, 4081, 4082, 4083, 4084, 4085, 4086, 4087, 4088, 4089, 4090, 4091, 4092, 4093, 4094, 4095 ]; + gamma = 100; + contrast = 100; + black_level = 0; + white_level = 256; +}; +isp_shape : +{ + noise_reduce = false; + vflip = false; + hflip = false; + rotate_dir = 0; + sharpness = 0; + defect_corr = true; + flat_fielding_corr_enable = false; + flat_fielding_corr_param_file_path = ""; + denoise3d_enable = false; + denoise3d_length = 0; + denoise3d_use_weight = false; +}; +trigger_set : +{ + count_per_trigger = 1; + enable_trigger = false; + trigger_sel = 0; + ext_trig_delay_time = 0; + ext_trig_signal_type = 0; + ext_trig_shutter_type = 0; + strobe_pulse_width = 10; + strobe_delay_time = 50; + strobe_polarity = 0; + strobe_mode = 1; + jitter_time = 50000; +}; +wdr : +{ + awdr_enable = false; +}; diff --git a/others/include/camera/CameraApi.h b/others/include/camera/CameraApi.h new file mode 100644 index 0000000..bf8d377 --- /dev/null +++ b/others/include/camera/CameraApi.h @@ -0,0 +1,4842 @@ +#ifndef _MVCAMAPI_H_ +#define _MVCAMAPI_H_ + + +#ifdef DLL_EXPORT +#define MVSDK_API extern "C" __declspec(dllexport) +#else +#define MVSDK_API extern "C" __declspec(dllimport) +#endif +#include +#include "CameraDefine.h" +#include "CameraStatus.h" + +/// @ingroup API_BASIC +/// \~chinese +/// \brief ʼSDKԡúڼֻҪһΡ +/// \param [in] iLanguageSel ѡSDKڲʾϢͽ,0:ʾӢ,1:ʾġ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Initialize the SDK language. This function only needs to be called once during the entire process run. +/// \param [in] iLanguageSel The language used to select the prompt information and interface of the SDK. 0: English, 1: Chinese. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSdkInit( + int iLanguageSel +); + +/// @ingroup API_ENUM +/// \~chinese +/// \brief ö豸豸б +/// \param [out] pCameraList 豸бָ +/// \param [inout] piNums 豸ĸָ룬ʱpCameraListԪظʱʵҵ豸 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ +/// \warning piNumsֵָʼҲpCameraListԪظпڴ +/// \note صϢбacFriendlyNameġԽֱΪCamera1͡Camera2ֺΪCamera1ǰ棬ΪCamera2ź档 +/// \~english +/// \brief Enumerate devices and establish a list of devices +/// \param [out] pCameraList Device list array pointer +/// \param [inout] piNums The number of pointers to the device, the number of elements passed to the pCameraList array at the time of the call. When the function returns, the number of devices actually found is saved. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \warning piNums The value pointed to must be initialized and does not exceed the number of pCameraList array elements, otherwise it may cause memory overflow +/// \note The list of returned camera information will be sorted according to acFriendlyName. For example, after changing the two cameras to the names of "Camera1" and "Camera2," the camera named "Camera1" will be in front, and the camera named "Camera2" will be behind the row. +MVSDK_API CameraSdkStatus __stdcall CameraEnumerateDevice( + tSdkCameraDevInfo* pCameraList, + INT* piNums +); + +/// @ingroup API_ENUM +/// \~chinese +/// \brief ö豸豸бڵ@link #CameraInitEx @endlink֮ǰøúö豸 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Enumerate devices and create a list of devices. Before calling @link #CameraInitEx @endlink, this function must be called to enumerate the device. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API INT __stdcall CameraEnumerateDeviceEx( +); + +/// @ingroup API_OPEN +/// \~chinese +/// \brief 豸ǷѾ +/// \param [in] pCameraInfo 豸öϢṹָ룬@link #CameraEnumerateDevice @endlinká +/// \param [out] pOpened 豸״ָ̬룬豸Ƿ񱻴򿪵״̬TRUEΪ򿪣FALSEΪС +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Check if the device has been opened +/// \param [in] pCameraInfo Device enumeration information structure pointer, obtained by @link #CameraEnumerateDevice @endlink +/// \param [out] pOpened The device's status pointer returns whether the device is turned on. TRUE is on and FALSE is idle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraIsOpened( + tSdkCameraDevInfo* pCameraInfo, + BOOL* pOpened +); + +/// @ingroup API_OPEN +/// \~chinese +/// \brief ʼʼɹ󣬲ܵصIJӿڡ +/// \param [in] pCameraInfo 豸öϢṹָ룬@link #CameraEnumerateDevice @endlinká +/// \param [in] emParamLoadMode ʼʱʹõIJطʽ-1ʾʹϴ˳ʱIJطʽȡֵο@link #emSdkParameterMode @endlink塣 +/// \param [in] emTeam ʼʱʹõIJ顣-1ʾϴ˳ʱIJ顣 +/// \param [out] pCameraHandle ľָ룬ʼɹ󣬸ָ뷵ظЧ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief The camera is initialized. After successful initialization, other camera-related operation interfaces can be called. +/// \param [in] pCameraInfo Device enumeration information structure pointer, obtained by @link #CameraEnumerateDevice @endlink. +/// \param [in] emParamLoadMode The parameter loading method used when the camera is initialized. -1 means to use the parameter loading method from the last exit. Other values are defined in @link #emSdkParameterMode @endlink. +/// \param [in] emTeam Parameter group used during initialization. -1 means to load the parameter group from the last exit. +/// \param [out] pCameraHandle The handle pointer of the camera, after successful initialization, returns the camera's effective handle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraInit( + tSdkCameraDevInfo* pCameraInfo, + int emParamLoadMode, + int emTeam, + CameraHandle* pCameraHandle +); + +/// @ingroup API_OPEN +/// \~chinese +/// \brief ʼʼɹ󣬲ܵصIJӿڡ +/// \param [in] iDeviceIndex ţ@link #CameraEnumerateDeviceEx @endlink +/// \param [in] emParamLoadMode ʼʱʹõIJطʽ-1ʾʹϴ˳ʱIJطʽȡֵο@link #emSdkParameterMode @endlink塣 +/// \param [in] emTeam ʼʱʹõIJ顣-1ʾϴ˳ʱIJ顣 +/// \param [out] pCameraHandle ľָ룬ʼɹ󣬸ָ뷵ظЧ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief The camera is initialized. After successful initialization, other camera-related operation interfaces can be called. +/// \param [in] iDeviceIndex The camera's index number, @link #CameraEnumerateDeviceEx @endlink returns the number of cameras. +/// \param [in] emParamLoadMode The parameter loading method used when the camera is initialized. -1 means to use the parameter loading method from the last exit. Other values are defined in @link #emSdkParameterMode @endlink. +/// \param [in] emTeam Parameter group used during initialization. -1 means to load the parameter group from the last exit. +/// \param [out] pCameraHandle The handle pointer of the camera, after successful initialization, returns the camera's effective handle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraInitEx( + int iDeviceIndex, + int emParamLoadMode, + int emTeam, + CameraHandle* pCameraHandle +); + +/// @ingroup API_OPEN +/// \~chinese +/// \brief ʼʼɹ󣬲ܵصIJӿڡ +/// \param [in] CameraName dzơ@link #tSdkCameraDevInfo.acFriendlyName @endlink +/// \param [out] pCameraHandle ľָ룬ʼɹ󣬸ָ뷵ظЧ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief The camera is initialized. After successful initialization, other camera-related operation interfaces can be called. +/// \param [in] CameraName Camera friendly name.@link #tSdkCameraDevInfo.acFriendlyName @endlink +/// \param [out] pCameraHandle The handle pointer of the camera, after successful initialization, returns the camera's effective handle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraInitEx2( + char* CameraName, + CameraHandle *pCameraHandle +); + +/// @ingroup API_GRAB_CB +/// \~chinese +/// \brief ͼ񲶻Ļصµͼ֡ʱpCallBackָĻصͻᱻá +/// \param [in] hCamera ľ +/// \param [in] pCallBack صָ롣 +/// \param [in] pContext صĸӲڻصʱøӲᱻ룬ΪNULLڶʱЯϢ +/// \param [out] pCallbackOld ڷ֮ǰõĻصΪNULL +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Sets the image capture's callback function. When a new frame of image data is captured, the callback function pointed to by pCallBack is called. +/// \param [in] hCamera Camera handle. +/// \param [in] pCallBack Callback function pointer. +/// \param [in] pContext Additional parameters of the callback function, which will be passed in when the callback function is called, can be NULL. Use additional information when used with multiple cameras. +/// \param [out] pCallbackOld Returns the previously set callback function. Can be NULL. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetCallbackFunction( + CameraHandle hCamera, + CAMERA_SNAP_PROC pCallBack, + PVOID pContext, + CAMERA_SNAP_PROC* pCallbackOld +); + +/// @ingroup API_CLOSE +/// \~chinese +/// \brief ʼͷԴ +/// \param [in] hCamera ľ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief The camera is deinitialized. Release resources. +/// \param [in] hCamera Camera handle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraUnInit( + CameraHandle hCamera +); + +/// @ingroup API_BASIC +/// \~chinese +/// \brief Ϣ +/// \param [in] hCamera ľ +/// \param [out] pbuffer ָϢָָ롣 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get camera description information +/// \param [in] hCamera Camera handle. +/// \param [out] pbuffer Pointer to the camera description information pointer. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetInformation( + CameraHandle hCamera, + char** pbuffer +); + +/// @ingroup API_ISP +/// \~chinese +/// \brief õԭʼͼݽдӱͶȡɫУȴЧõRGB888ʽͼݡ +/// \param [in] hCamera ľ +/// \param [in] pbyIn ͼݵĻַΪNULL +/// \param [out] pbyOut ͼĻַΪNULL +/// \param [inout] pFrInfo ͼ֡ͷϢɺ֡ͷϢеͼʽuiMediaType֮ı䡣 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief The obtained raw camera output image data is processed to superimpose processing effects such as saturation, color gain and correction, noise reduction, etc. Finally, image data of RGB888 format is obtained. +/// \param [in] hCamera Camera handle. +/// \param [in] pbyIn The buffer address of the input image data cannot be NULL. +/// \param [out] pbyOut The buffer address of the image output after processing cannot be NULL. +/// \param [inout] pFrInfo After inputting the frame header information of the image, the image format uiMediaType in the frame header information will be changed after the processing is completed. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImageProcess( + CameraHandle hCamera, + BYTE* pbyIn, + BYTE* pbyOut, + tSdkFrameHead* pFrInfo +); + +/// @ingroup API_ISP +/// \~chinese +/// \brief õԭʼͼݽдӱͶȡɫУȴЧõRGB888ʽͼݡ +/// \param [in] hCamera ľ +/// \param [in] pbyIn ͼݵĻַΪNULL +/// \param [out] pbyOut ͼĻַΪNULL +/// \param [inout] pFrInfo ͼ֡ͷϢɺ֡ͷϢеͼʽuiMediaType֮ı䡣 +/// \param [in] uOutFormat ͼʽCAMERA_MEDIA_TYPE_MONO8CAMERA_MEDIA_TYPE_RGBCAMERA_MEDIA_TYPE_RGBA8һ֡ +/// \param [in] uReserved ԤΪ0 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief The obtained raw camera output image data is processed to superimpose processing effects such as saturation, color gain and correction, noise reduction, etc. Finally, image data of RGB888 format is obtained. +/// \param [in] hCamera Camera handle. +/// \param [in] pbyIn The buffer address of the input image data cannot be NULL. +/// \param [out] pbyOut The buffer address of the image output after processing cannot be NULL. +/// \param [inout] pFrInfo After inputting the frame header information of the image, the image format uiMediaType in the frame header information will be changed after the processing is completed. +/// \param [in] uOutFormat The output format of the image after processing. It may be one of CAMERA_MEDIA_TYPE_MONO8,CAMERA_MEDIA_TYPE_RGB,CAMERA_MEDIA_TYPE_RGBA8. +/// \param [in] uReserved Reservation parameters must be set to 0. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImageProcessEx( + CameraHandle hCamera, + BYTE* pbyIn, + BYTE* pbyOut, + tSdkFrameHead* pFrInfo, + UINT uOutFormat, + UINT uReserved +); + +/// @ingroup API_DISPLAY +/// \~chinese +/// \brief ʼSDKڲʾģ顣ڵ@link #CameraDisplayRGB24 @endlinkǰȵøúʼڶοУʹԼķʽͼʾ(CameraDisplayRGB24)Ҫñ +/// \param [in] hCamera ľ +/// \param [in] hWndDisplay ʾڵľһΪڵm_hWndԱ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Initialize the display module inside the SDK. The function must be called before calling @link #CameraDisplayRGB24 @endlink. If you use your own method for image display (do not call CameraDisplayRGB24) during secondary development, you do not need to call this function. +/// \param [in] hCamera Camera handle. +/// \param [in] hWndDisplay The handle of the display window, typically the m_hWnd member of the window. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraDisplayInit( + CameraHandle hCamera, + HWND hWndDisplay +); + +/// @ingroup API_DISPLAY +/// \~chinese +/// \brief ʾͼ񡣱ù@link #CameraDisplayInit @endlinkгʼܵñ +/// \param [in] hCamera ľ +/// \param [in] pFrameBuffer ͼ֡ +/// \param [in] pFrInfo ͼ֡ͷϢ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Display the image. You must call @link #CameraDisplayInit @endlink before you can call this function. +/// \param [in] hCamera Camera handle. +/// \param [in] pFrameBuffer Image frame buffer +/// \param [in] pFrInfo The frame header information of the image +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraDisplayRGB24( + CameraHandle hCamera, + BYTE* pFrameBuffer, + tSdkFrameHead* pFrInfo +); + +/// @ingroup API_DISPLAY +/// \~chinese +/// \brief ʾģʽ +/// \param [in] hCamera ľ +/// \param [in] iMode ʾģʽμ@link #emSdkDisplayMode @endlinkĶ塣 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the display mode. +/// \param [in] hCamera Camera handle. +/// \param [in] iMode Display mode, see @link #emSdkDisplayMode @endlink definition. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetDisplayMode( + CameraHandle hCamera, + INT iMode +); + +/// @ingroup API_DISPLAY +/// \~chinese +/// \brief ʾʼƫֵʾģʽΪDISPLAYMODE_REALʱЧʾؼĴСΪ320X240ͼĵijߴΪ640X480ôiOffsetX = 160,iOffsetY = 120ʱʾͼľ320X240λá +/// \param [in] hCamera ľ +/// \param [in] iOffsetX ƫƵXꡣ +/// \param [in] iOffsetY ƫƵYꡣ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the starting offset of the display. This is valid only when the display mode is DISPLAY MODE_REAL. For example, the size of the display control is 320240, and the size of the image is 640480. When iOffsetX = 160 and iOffsetY = 120, the displayed area is the center 320240 of the image. +/// \param [in] hCamera Camera handle. +/// \param [in] iOffsetX The offset's X coordinate. +/// \param [in] iOffsetY The offset's Y coordinate. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetDisplayOffset( + CameraHandle hCamera, + int iOffsetX, + int iOffsetY +); + +/// @ingroup API_DISPLAY +/// \~chinese +/// \brief ʾؼijߴ硣 +/// \param [in] hCamera ľ +/// \param [in] iWidth +/// \param [in] iHeight ߶ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the size of the display control. +/// \param [in] hCamera Camera handle. +/// \param [in] iWidth width +/// \param [in] iHeight height +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetDisplaySize( + CameraHandle hCamera, + INT iWidth, + INT iHeight +); + +/// @ingroup API_GRAB +/// \~chinese +/// \brief һ֡ͼݡΪЧʣSDKͼץȡʱ㿽ƣʵʻںеһַ +/// \param [in] hCamera ľ +/// \param [out] pFrameInfo ͼ֡ͷϢָ롣 +/// \param [out] pbyBuffer ͼݵĻָ롣 +/// \param [in] wTimes ץȡͼijʱʱ䣬λ롣wTimesʱڻδͼú᷵سʱ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note úɹú󣬱@link CameraReleaseImageBuffer @endlinkͷŻ,Աں˼ʹøû +/// \~english +/// \brief Get a frame of image data. To improve efficiency, the SDK uses a zero-copy mechanism for image capture. This function actually obtains a buffer address in the kernel. +/// \param [in] hCamera Camera handle. +/// \param [out] pFrameInfo The header information pointer of the image. +/// \param [out] pbyBuffer Returns the buffer pointer of the image data. +/// \param [in] wTimes Timeout for grabbing an image in milliseconds. The function returns a timeout error if no image has been obtained within wTimes. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note After the function is successfully called, @link CameraReleaseImageBuffer @endlink must be called to release the buffer so that the kernel can continue to use the buffer. +MVSDK_API CameraSdkStatus __stdcall CameraGetImageBuffer( + CameraHandle hCamera, + tSdkFrameHead* pFrameInfo, + BYTE** pbyBuffer, + UINT wTimes +); + +/// @ingroup API_GRAB +/// \~chinese +/// \brief һ֡ͼݡýӿڻõͼѾͼݡ +/// \param [in] hCamera ľ +/// \param [out] piWidth ָ룬ͼĿȡ +/// \param [out] piHeight ָ룬ͼĸ߶ȡ +/// \param [in] wTimes ץȡͼijʱʱ䣬λ롣wTimesʱڻδͼú᷵سʱ +/// \return ɹʱ֡ݻ׵ַ򷵻0 +/// \note Ҫ@link CameraReleaseImageBuffer @endlinkͷŻ +/// \~english +/// \brief Get a frame of image data. The image data obtained by this interface is already image-processed data. +/// \param [in] hCamera Camera handle. +/// \param [out] piWidth returns the width of the image. +/// \param [out] piHeight Returns the height of the image. +/// \param [in] wTimes Timeout for grabbing an image in milliseconds. The function returns a timeout error if no image has been obtained within wTimes. +/// \return On success, returns the first address of the frame data buffer, otherwise it returns 0. +/// \note This function does not need to call @link CameraReleaseImageBuffer @endlink to release the buffer. +MVSDK_API unsigned char* __stdcall CameraGetImageBufferEx( + CameraHandle hCamera, + INT* piWidth, + INT* piHeight, + UINT wTimes +); + +/// @ingroup API_GRAB +/// \~chinese +/// \brief ץһͼ񵽻СץģʽԶлץģʽķֱʽͼ񲶻 +/// \param [in] hCamera ľ +/// \param [out] pFrameInfo ͼ֡ͷϢָ롣 +/// \param [out] pbyBuffer ͼݵĻָ롣 +/// \param [in] wTimes ץȡͼijʱʱ䣬λ롣wTimesʱڻδͼú᷵سʱ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note úɹú󣬱@link CameraReleaseImageBuffer @endlinkͷŻ,Աں˼ʹøû +/// \warning ܻзֱлЧʻ@link #CameraGetImageBuffer @endlink͡ûлֱץĵʹ@link #CameraGetImageBuffer @endlink +/// \~english +/// \brief Take an image into the buffer. The camera will enter snap mode and automatically switch to snap mode resolution for image capture. +/// \param [in] hCamera Camera handle. +/// \param [out] pFrameInfo The header information pointer of the image. +/// \param [out] pbyBuffer Returns the buffer pointer of the image data. +/// \param [in] wTimes Timeout for grabbing an image in milliseconds. The function returns a timeout error if no image has been obtained within wTimes. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note After the function is successfully called, @link CameraReleaseImageBuffer @endlink must be called to release the buffer so that the kernel can continue to use the buffer. +/// \warning This function may switch the resolution, so the efficiency will be lower than @link #CameraGetImageBuffer @endlink. If you do not need to switch resolution capture, use @link #CameraGetImageBuffer @endlink. +MVSDK_API CameraSdkStatus __stdcall CameraSnapToBuffer( + CameraHandle hCamera, + tSdkFrameHead* pFrameInfo, + BYTE** pbyBuffer, + UINT wTimes +); + +/// @ingroup API_GRAB +/// \~chinese +/// \brief ͷ@link #CameraGetImageBuffer @endlinkõĻ +/// \param [in] hCamera ľ +/// \param [in] pbyBuffer ַ֡ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Releases the buffer obtained by @link #CameraGetImageBuffer @endlink. +/// \param [in] hCamera Camera handle. +/// \param [in] pbyBuffer Frame buffer address. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraReleaseImageBuffer( + CameraHandle hCamera, + BYTE* pbyBuffer +); + +/// @ingroup API_PLAY_CTRL +/// \~chinese +/// \brief 빤ģʽʼ͵ͼݡ +/// \param [in] hCamera ľ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Put the camera into working mode and start receiving image data from the camera. +/// \param [in] hCamera Camera handle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraPlay( + CameraHandle hCamera +); + +/// @ingroup API_PLAY_CTRL +/// \~chinese +/// \brief ͣģʽͼݣͬʱҲᷢͣͷŴͣģʽ£ԶIJãЧ +/// \param [in] hCamera ľ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Put the camera into pause mode, do not receive image data from the camera, and also send a command to pause the camera output and release the transmission bandwidth. In pause mode, camera parameters can be configured and take effect immediately. +/// \param [in] hCamera Camera handle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraPause( + CameraHandle hCamera +); + +/// @ingroup API_PLAY_CTRL +/// \~chinese +/// \brief ֹͣ״̬һǷʼʱøúúãٶIJá +/// \param [in] hCamera ľ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Let the camera enter the stop state. Generally, this function is called when deinitializing. The function is called and the camera parameters cannot be configured. +/// \param [in] hCamera Camera handle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraStop( + CameraHandle hCamera +); + +/// @ingroup API_RECORD +/// \~chinese +/// \brief ʼһ¼ +/// \param [in] hCamera ľ +/// \param [in] iFormat ¼ĸʽǰֲֻ֧ѹMSCVַʽ0:ѹ 1:MSCVʽѹ +/// \param [in] pcSavePath ¼ļ· +/// \param [in] b2GLimit ΪTRUE,ļ2GʱԶָδʵ֣ +/// \param [in] dwQuality ¼ӣԽԽáΧ1100. +/// \param [in] iFrameRate ¼֡ʡ趨ıʵʲɼ֡ʴͲ©֡ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Initialize a video. +/// \param [in] hCamera Camera handle. +/// \param [in] iFormat The video format currently supports only the uncompressed and MSCV modes. 0: No compression 1: MSCV compression. +/// \param [in] pcSavePath The path to save the video file. +/// \param [in] b2GLimit If TRUE, the file is automatically split when it is larger than 2G. (Function not implemented) +/// \param [in] dwQuality The larger the quality factor of the video, the better the quality. Range 1 to 100. +/// \param [in] iFrameRate The frame rate of the video. It is recommended to set a larger frame rate than the actual acquisition so that no frames are missed. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraInitRecord( + CameraHandle hCamera, + int iFormat, + char* pcSavePath, + BOOL b2GLimit, + DWORD dwQuality, + int iFrameRate +); + +/// @ingroup API_RECORD +/// \~chinese +/// \brief ¼񡣵@link #CameraInitRecord @endlink󣬿ͨúһ¼񣬲ļ +/// \param [in] hCamera ľ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief End this video. After @link #CameraInitRecord @endlink, you can use this function to end a video and complete the file save operation. +/// \param [in] hCamera Camera handle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraStopRecord( + CameraHandle hCamera +); + +/// @ingroup API_RECORD +/// \~chinese +/// \brief һ֡ݴ¼Сǵ֡ͷϢЯͼɼʱϢ¼Ծ׼ʱͬ֡ʲȶӰ졣 +/// \param [in] hCamera ľ +/// \param [in] pbyImageBuffer ͼݻ +/// \param [in] pFrInfo ͼ֡ͷϢ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief One frame of data is stored in the video stream. Since our frame header information carries the timestamp information of the image acquisition, the recording can be accurately time synchronized without being affected by the instability of the frame rate. +/// \param [in] hCamera Camera handle. +/// \param [in] pbyImageBuffer Image data buffer. +/// \param [in] pFrInfo The frame header information of the image. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraPushFrame( + CameraHandle hCamera, + BYTE* pbyImageBuffer, + tSdkFrameHead* pFrInfo +); + +/// @ingroup API_SAVE_IMAGE +/// \~chinese +/// \brief ͼ񻺳ݱͼƬļ +/// \param [in] hCamera ľ +/// \param [in] lpszFileName ͼƬļ· +/// \param [in] pbyImageBuffer ͼݻ +/// \param [in] pFrInfo ͼ֡ͷϢ +/// \param [in] byFileType ͼ񱣴ĸʽȡֵΧμ@link #emSdkFileType @endlinkĶ塣 +/// \param [in] byQuality ͼ񱣴ӣΪJPGʽʱòЧΧ1100ʽд0 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note Ŀǰ֧ BMPJPGPNGRAWָʽRAWʾԭʼݣRAWʽļҪpbyImageBufferpFrInfo@link #CameraGetImageBuffer @endlinkõݣδ@link #CameraImageProcess @endlinkתBMPʽ֮ҪBMPJPGPNGʽpbyImageBufferpFrInfo@link #CameraImageProcess @endlinkRGBʽݡ÷ԲοAdvanced̡ +/// \~english +/// \brief Save the image buffer data as a picture file. +/// \param [in] hCamera Camera handle. +/// \param [in] lpszFileName The picture saves the full path to the file. +/// \param [in] pbyImageBuffer Image data buffer. +/// \param [in] pFrInfo The frame header information of the image. +/// \param [in] byFileType Image save format. See the definition of @link #emSdkFileType @endlink for the range of values. +/// \param [in] byQuality The quality factor of the saved image. This parameter is valid only when saving in JPG format. The range is from 1 to 100. The rest of the format can be written as 0. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note Currently supports BMP, JPG, PNG, RAW four formats. Among them, RAW represents the raw data output by the camera. Saving RAW format files requires pbyImageBuffer and pFrInfo to be obtained by @link #CameraGetImageBuffer @endlink, and without @link #CameraImageProcess @endlink converting to BMP format; otherwise, if you want to save to BMP JPG or PNG format, pbyImageBuffer and pFrInfo are RGB format data processed by @link #CameraImageProcess @endlink. Specific usage can refer to Advanced's routines. +MVSDK_API CameraSdkStatus __stdcall CameraSaveImage( + CameraHandle hCamera, + char* lpszFileName, + BYTE* pbyImageBuffer, + tSdkFrameHead* pFrInfo, + UINT byFileType, + BYTE byQuality +); + +/// @ingroup API_SAVE_IMAGE +/// \~chinese +/// \brief ͼ񻺳ݱͼƬļ +/// \param [in] hCamera ľ +/// \param [in] lpszFileName ͼƬļ· +/// \param [in] pbyImageBuffer ͼݻ +/// \param [in] uImageFormat 0:8 BIT gray 1:rgb24 2:rgba32 3:bgr24 4:bgra32 +/// \param [in] iWidth ͼƬ +/// \param [in] iHeight ͼƬ߶ +/// \param [in] byFileType ͼ񱣴ĸʽȡֵΧμ@link #emSdkFileType @endlinkĶ塣 +/// \param [in] byQuality ͼ񱣴ӣΪJPGʽʱòЧΧ1100ʽд0 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note @link #CameraSaveImage @endlinkͬ +/// \~english +/// \brief Save the image buffer data as a picture file. +/// \param [in] hCamera Camera handle. +/// \param [in] lpszFileName The picture saves the full path to the file. +/// \param [in] pbyImageBuffer Image data buffer. +/// \param [in] uImageFormat 0:8 BIT gray 1:rgb24 2:rgba32 3:bgr24 4:bgra32 +/// \param [in] iWidth width +/// \param [in] iHeight height +/// \param [in] byFileType Image save format. See the definition of @link #emSdkFileType @endlink for the range of values. +/// \param [in] byQuality The quality factor of the saved image. This parameter is valid only when saving in JPG format. The range is from 1 to 100. The rest of the format can be written as 0. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note Same as @link #CameraSaveImage @endlink +MVSDK_API CameraSdkStatus __stdcall CameraSaveImageEx( + CameraHandle hCamera, + char* lpszFileName, + BYTE* pbyImageBuffer, + UINT uImageFormat, + int iWidth, + int iHeight, + UINT byFileType, + BYTE byQuality + ); + +/// @ingroup API_ROI +/// \~chinese +/// \brief õǰԤķֱʡ +/// \param [in] hCamera ľ +/// \param [out] psCurVideoSize صǰķֱʡ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the current preview resolution. +/// \param [in] hCamera Camera handle. +/// \param [out] psCurVideoSize Returns the current resolution. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetImageResolution( + CameraHandle hCamera, + tSdkImageResolution* psCurVideoSize +); + +/// @ingroup API_ROI +/// \~chinese +/// \brief õǰԤķֱʡ +/// \param [in] hCamera ľ +/// \param [out] iIndex ţ[0,N]ʾԤķֱ(N ΪԤֱʵһ㲻20),OXFF ʾԶֱ(ROI) +/// \param [out] acDescription ÷ֱʵϢԤֱʱϢЧԶֱʿɺԸϢ +/// \param [out] Mode 0: ͨģʽ 1Sum 2Average 3Skip 4Resample +/// \param [out] ModeSize ͨģʽºԣ1λʾ2X2 ڶλʾ3X3 ... +/// \param [out] x ˮƽƫ +/// \param [out] y ֱƫ +/// \param [out] width +/// \param [out] height +/// \param [out] ZoomWidth ʱſȣ0ʾ +/// \param [out] ZoomHeight ʱŸ߶ȣ0ʾ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the current preview resolution. +/// \param [in] hCamera Camera handle. +/// \param [out] iIndex Index number, [0,N] indicates the default resolution (N is the maximum number of preset resolutions, generally no more than 20), OXFF indicates custom resolution (ROI) +/// \param [out] acDescription Descriptive information for this resolution. This information is valid only when the resolution is preset. Custom resolution ignores this information +/// \param [out] Mode 0: Normal Mode 1:Sum 2:Average 3:Skip 4:Resample +/// \param [out] ModeSize ignored in normal mode, the first bit represents 2X2 the second bit represents 3X3 ... +/// \param [out] x horizontal offset +/// \param [out] y vertical offset +/// \param [out] width width +/// \param [out] height high +/// \param [out] ZoomWidth Scale width when final output, 0 means not zoom +/// \param [out] ZoomHeight Scales the height of the final output, 0 means no scaling +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetImageResolutionEx( + CameraHandle hCamera, + int* iIndex, + char acDescription[32], + int* Mode, + UINT* ModeSize, + int* x, + int* y, + int* width, + int* height, + int* ZoomWidth, + int* ZoomHeight + ); + +/// @ingroup API_ROI +/// \~chinese +/// \brief Ԥķֱʡ +/// \param [in] hCamera ľ +/// \param [in] pImageResolution ·ֱʡ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Sets the resolution of the preview. +/// \param [in] hCamera Camera handle. +/// \param [in] pImageResolution New resolution. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetImageResolution( + CameraHandle hCamera, + tSdkImageResolution* pImageResolution +); + +/// @ingroup API_ROI +/// \~chinese +/// \brief õǰԤķֱʡ +/// \param [in] hCamera ľ +/// \param [in] iIndex ţ[0,N]ʾԤķֱ(N ΪԤֱʵһ㲻20),OXFF ʾԶֱ(ROI) +/// \param [in] Mode 0: ͨģʽ 1Sum 2Average 3Skip 4Resample +/// \param [in] ModeSize ͨģʽºԣ1λʾ2X2 ڶλʾ3X3 ... +/// \param [in] x ˮƽƫ +/// \param [in] y ֱƫ +/// \param [in] width +/// \param [in] height +/// \param [in] ZoomWidth ʱſȣ0ʾ +/// \param [in] ZoomHeight ʱŸ߶ȣ0ʾ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the current preview resolution. +/// \param [in] hCamera Camera handle. +/// \param [in] iIndex Index number, [0,N] indicates the default resolution (N is the maximum number of preset resolutions, generally no more than 20), OXFF indicates custom resolution (ROI) +/// \param [in] Mode 0: Normal Mode 1:Sum 2:Average 3:Skip 4:Resample +/// \param [in] ModeSize ignored in normal mode, the first bit represents 2X2 the second bit represents 3X3 ... +/// \param [in] x horizontal offset +/// \param [in] y vertical offset +/// \param [in] width width +/// \param [in] height high +/// \param [in] ZoomWidth Scale width when final output, 0 means not zoom +/// \param [in] ZoomHeight Scales the height of the final output, 0 means no scaling +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetImageResolutionEx( + CameraHandle hCamera, + int iIndex, + int Mode, + UINT ModeSize, + int x, + int y, + int width, + int height, + int ZoomWidth, + int ZoomHeight + ); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief ǰԭʼݵĸʽš +/// \param [in] hCamera ľ +/// \param [out] piMediaType صǰʽ͵š +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note @link #tSdkCameraCapbility.pMediaTypeDesc @endlinkԱУʽֵ֧ĸʽpiMediaTypeָţǸš +/// \~english +/// \brief Gets the format index number of the camera's current output raw data. +/// \param [in] hCamera Camera handle. +/// \param [out] piMediaType Returns the index of the current format type. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note In the @link #tSdkCameraCapbility.pMediaTypeDesc @endlink member, the format supported by the camera is saved as an array. The index number pointed to by piMediaType is the index number of the array. +MVSDK_API CameraSdkStatus __stdcall CameraGetMediaType( + CameraHandle hCamera, + INT* piMediaType +); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief ԭʼݸʽ +/// \param [in] hCamera ľ +/// \param [in] iMediaType ¸ʽ͵š +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note @link #CameraGetMediaType @endlinkͬ +/// \~english +/// \brief Sets the camera's output raw data format. +/// \param [in] hCamera Camera handle. +/// \param [in] iMediaType The index number of the new format type. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note Same as @link #CameraGetMediaType @endlink. +MVSDK_API CameraSdkStatus __stdcall CameraSetMediaType( + CameraHandle hCamera, + INT iMediaType +); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief عģʽԶֶ +/// \param [in] hCamera ľ +/// \param [in] bAeState TRUE:Զع⣻FALSE:ֶع⡣ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the camera exposure mode. Automatic or manual. +/// \param [in] hCamera Camera handle. +/// \param [in] bAeState TRUE: Auto exposure; FALSE: Manual exposure. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetAeState( + CameraHandle hCamera, + BOOL bAeState +); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief ǰعģʽ +/// \param [in] hCamera ľ +/// \param [out] pAeState Զعʹ״̬ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the camera's current exposure mode. +/// \param [in] hCamera Camera handle. +/// \param [out] pAeState Returns the auto exposure's enable state. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetAeState( + CameraHandle hCamera, + BOOL* pAeState +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief ͼĴ񻯲 +/// \param [in] hCamera ľ +/// \param [in] iSharpness 񻯲һ[0,100]0ʾر񻯴 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Sets the sharpening parameters for the processing of the image. +/// \param [in] hCamera Camera handle. +/// \param [in] iSharpness Sharpen parameter, generally [0,100], 0 means close sharpening. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetSharpness( + CameraHandle hCamera, + int iSharpness +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief ȡǰ趨ֵ +/// \param [in] hCamera ľ +/// \param [out] piSharpness صǰ趨񻯵趨ֵ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Gets the current sharpening setting. +/// \param [in] hCamera Camera handle. +/// \param [out] piSharpness Returns the currently set sharpened setting. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetSharpness( + CameraHandle hCamera, + int* piSharpness +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief IJ任ģʽLUTģʽ +/// \param [in] hCamera ľ +/// \param [in] emLutMode ο@link #emSdkLutMode @endlink͡ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the camera's lookup table transformation mode LUT mode. +/// \param [in] hCamera Camera handle. +/// \param [in] emLutMode Defines the reference @link #emSdkLutMode @endlink type. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetLutMode( + CameraHandle hCamera, + int emLutMode +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief IJ任ģʽLUTģʽ +/// \param [in] hCamera ľ +/// \param [out] pemLutMode صǰLUTģʽ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Obtain the look-up table conversion mode LUT mode of the camera. +/// \param [in] hCamera Camera handle. +/// \param [out] pemLutMode Returns the current LUT mode. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetLutMode( + CameraHandle hCamera, + int* pemLutMode +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief ѡԤLUTģʽµLUT +/// \param [in] hCamera ľ +/// \param [in] iSel šĸ@link #tSdkCameraCapbility.iPresetLut @endlinká +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ʹ@link #CameraSetLutMode @endlinkLUTģʽΪԤģʽ +/// \~english +/// \brief Select the LUT table in the preset LUT mode. +/// \param [in] hCamera Camera handle. +/// \param [in] iSel The index number of the lut table. The number of tables is obtained by @link #tSdkCameraCapbility.iPresetLut @endlink. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note Must use @link #CameraSetLutMode @endlink to set LUT mode to preset mode. +MVSDK_API CameraSdkStatus __stdcall CameraSelectLutPreset( + CameraHandle hCamera, + int iSel +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief ԤLUTģʽµLUTš +/// \param [in] hCamera ľ +/// \param [out] piSel رš +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief The LUT table index number in the preset LUT mode is obtained. +/// \param [in] hCamera Camera handle. +/// \param [out] piSel Returns the index number of the table. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetLutPresetSel( + CameraHandle hCamera, + int* piSel +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief ԶLUT +/// \param [in] hCamera ľ +/// \param [in] iChannel ָҪ趨LUTɫͨΪ@link #LUT_CHANNEL_ALL @endlinkʱͨLUTͬʱ滻@see emSdkLutChannel +/// \param [in] pLut ָ룬ָLUTĵַLUTΪ޷Ŷ飬СΪ4096ֱɫͨ04096(12bitɫ)Ӧӳֵ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ʹ@link #CameraSetLutMode @endlinkLUTģʽΪԶģʽ +/// \~english +/// \brief Set up a custom LUT table. +/// \param [in] hCamera Camera handle. +/// \param [in] iChannel Specifies the LUT color channel to be set. When @link #LUT_CHANNEL_ALL @endlink, the three-channel LUTs will be replaced at the same time. @see emSdkLutChannel +/// \param [in] pLut pointer to the address of the LUT table. The LUT table is an unsigned short integer array, and the array size is 4096, which is the mapping value corresponding to the code color channel from 0 to 4096 (12 bit color accuracy). +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note You must use @link #CameraSetLutMode @endlink to set the LUT mode to custom mode. +MVSDK_API CameraSdkStatus __stdcall CameraSetCustomLut( + CameraHandle hCamera, + int iChannel, + USHORT* pLut +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief õǰʹõԶLUT +/// \param [in] hCamera ľ +/// \param [in] iChannel ָҪȡLUTɫͨΪ@link #LUT_CHANNEL_ALL @endlinkʱغɫͨLUT@see emSdkLutChannel +/// \param [out] pLut ָLUTĵַLUTΪ޷Ŷ飬СΪ4096ֱɫͨ04096(12bitɫ)Ӧӳֵ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the currently used custom LUT table. +/// \param [in] hCamera Camera handle. +/// \param [in] iChannel Specifies the LUT color channel to be obtained. When @link #LUT_CHANNEL_ALL @endlink, returns the LUT table of the red channel. @see emSdkLutChannel +/// \param [out] pLut points to the address of the LUT table. The LUT table is an unsigned short integer array, and the array size is 4096, which is the mapping value corresponding to the code color channel from 0 to 4096 (12 bit color accuracy). +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetCustomLut( + CameraHandle hCamera, + int iChannel, + USHORT* pLut +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief ǰLUTκLUTģʽ¶Ե,ֱ۵Ĺ۲LUTߵı仯 +/// \param [in] hCamera ľ +/// \param [in] iChannel ָҪȡLUTɫͨΪ@link #LUT_CHANNEL_ALL @endlinkʱغɫͨLUT@see emSdkLutChannel +/// \param [out] pLut ָLUTĵַLUTΪ޷Ŷ飬СΪ4096ֱɫͨ04096(12bitɫ)Ӧӳֵ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Obtain the camera's current LUT table, which can be called in any LUT mode, to intuitively observe changes in the LUT curve. +/// \param [in] hCamera Camera handle. +/// \param [in] iChannel Specifies the LUT color channel to be obtained. When @link #LUT_CHANNEL_ALL @endlink, returns the LUT table of the red channel. @see emSdkLutChannel +/// \param [out] pLut points to the address of the LUT table. The LUT table is an unsigned short integer array, and the array size is 4096, which is the mapping value corresponding to the code color channel from 0 to 4096 (12 bit color accuracy). +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetCurrentLut( + CameraHandle hCamera, + int iChannel, + USHORT* pLut +); + +/// @ingroup API_COLOR +/// \~chinese +/// \brief ƽģʽΪֶԶַʽ +/// \param [in] hCamera ľ +/// \param [in] bAuto TRUEʾʹԶģʽ FALSEʾʹֶģʽͨ@link #CameraSetOnceWB @endlinkһΰƽ⡣ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set camera white balance mode. Divided into manual and automatic two ways. +/// \param [in] hCamera Camera handle. +/// \param [in] bAuto TRUE to enable auto mode. FALSE indicates that using manual mode, a white balance is performed by calling @link #CameraSetOnceWB @endlink. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetWbMode( + CameraHandle hCamera, + BOOL bAuto +); + +/// @ingroup API_COLOR +/// \~chinese +/// \brief õǰİƽģʽ +/// \param [in] hCamera ľ +/// \param [out] pbAuto ָ룬TRUEʾԶģʽFALSEΪֶģʽ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the current white balance mode. +/// \param [in] hCamera Camera handle. +/// \param [out] pbAuto pointer, return TRUE for automatic mode, FALSE for manual mode. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetWbMode( + CameraHandle hCamera, + BOOL* pbAuto +); + +/// @ingroup API_COLOR +/// \~chinese +/// \brief ѡָԤɫģʽ +/// \param [in] hCamera ľ +/// \param [in] iSel Ԥɫµģʽţ0ʼ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note @link #CameraSetClrTempMode @endlinkΪԤģʽ +/// \~english +/// \brief Select the specified preset color temperature mode +/// \param [in] hCamera Camera handle. +/// \param [in] iSel The mode index number of the preset color temperature, starting from 0 +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note Call @link #CameraSetClrTempMode @endlink set to preset mode. +MVSDK_API CameraSdkStatus __stdcall CameraSetPresetClrTemp( + CameraHandle hCamera, + int iSel +); + +/// @ingroup API_COLOR +/// \~chinese +/// \brief õǰѡԤɫģʽ +/// \param [in] hCamera ľ +/// \param [out] piSel ѡԤɫ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the currently selected preset color temperature mode. +/// \param [in] hCamera Camera handle. +/// \param [out] piSel Returns the selected preset color temperature index number +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetPresetClrTemp( + CameraHandle hCamera, + int* piSel +); + +/// @ingroup API_COLOR +/// \~chinese +/// \brief Զɫģʽµ +/// \param [in] hCamera ľ +/// \param [in] iRgain ɫ棬Χ0400ʾ04 +/// \param [in] iGgain ɫ棬Χ0400ʾ04 +/// \param [in] iBgain ɫ棬Χ0400ʾ04 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note @link #CameraSetClrTempMode @endlinkΪԶģʽ +/// \~english +/// \brief Set digital gain in custom color temperature mode +/// \param [in] hCamera Camera handle. +/// \param [in] iRgain Red gain, range 0 to 400, 0 to 4 times +/// \param [in] iGgain Green gain, range 0 to 400, 0 to 4 times +/// \param [in] iBgain Blue gain, range 0 to 400, 0 to 4 times +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note Call @link #CameraSetClrTempMode @endlink set to custom mode. +MVSDK_API CameraSdkStatus __stdcall CameraSetUserClrTempGain( + CameraHandle hCamera, + int iRgain, + int iGgain, + int iBgain +); + +/// @ingroup API_COLOR +/// \~chinese +/// \brief Զɫģʽµ +/// \param [in] hCamera ľ +/// \param [out] piRgain ָ룬غɫ棬Χ0400ʾ04 +/// \param [out] piGgain ָ룬ɫ棬Χ0400ʾ04 +/// \param [out] piBgain ָ룬ɫ棬Χ0400ʾ04 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get digital gain in custom color temperature mode +/// \param [in] hCamera Camera handle. +/// \param [out] piRgain pointer, returning red gain, range 0 to 400, 0 to 4 times +/// \param [out] piGgain pointer, return green gain, range 0 to 400, 0 to 4 times +/// \param [out] piBgain pointer, returns blue gain, range 0 to 400, 0 to 4 times +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetUserClrTempGain( + CameraHandle hCamera, + int* piRgain, + int* piGgain, + int* piBgain +); + +/// @ingroup API_COLOR +/// \~chinese +/// \brief Զɫģʽµɫ +/// \param [in] hCamera ľ +/// \param [in] pMatrix ָһfloat[3][3]׵ַ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note @link #CameraSetClrTempMode @endlinkΪԶģʽ +/// \~english +/// \brief Set the color matrix in custom color temperature mode +/// \param [in] hCamera Camera handle. +/// \param [in] pMatrix points to the first address of an array of float[3][3] +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note Call @link #CameraSetClrTempMode @endlink set to custom mode. +MVSDK_API CameraSdkStatus __stdcall CameraSetUserClrTempMatrix( + CameraHandle hCamera, + float* pMatrix +); + +/// @ingroup API_COLOR +/// \~chinese +/// \brief Զɫģʽµɫ +/// \param [in] hCamera ľ +/// \param [out] pMatrix ָһfloat[3][3]׵ַ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the color matrix in a custom color temperature mode +/// \param [in] hCamera Camera handle. +/// \param [out] pMatrix points to the first address of an array of float[3][3] +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetUserClrTempMatrix( + CameraHandle hCamera, + float* pMatrix +); + +/// @ingroup API_COLOR +/// \~chinese +/// \brief ðƽʱʹõɫģʽ +/// \param [in] hCamera ľ +/// \param [in] iMode ģʽֻ@link #emSdkClrTmpMode @endlinkжһ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ֵ֧ģʽֱ֣ԶԤԶ塣 +/// \note Զģʽ£Զѡʵɫģʽ +/// \note Ԥģʽ£ʹûָɫģʽ +/// \note Զģʽ£ʹûԶɫ; +/// \~english +/// \brief Color temperature mode used when setting white balance +/// \param [in] hCamera Camera handle. +/// \param [in] iMode mode, can only be defined by @link #emSdkClrTmpMode @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note There are three supported modes, automatic, preset, and custom. +/// \note Automatic mode will automatically select the appropriate color temperature mode +/// \note In preset mode, user-specified color temperature mode is used +/// \note custom-defined color temperature digital gain and matrix +MVSDK_API CameraSdkStatus __stdcall CameraSetClrTempMode( + CameraHandle hCamera, + int iMode +); + +/// @ingroup API_COLOR +/// \~chinese +/// \brief ðƽʱʹõɫģʽο@link #CameraSetClrTempMode @endlinkй֡ +/// \param [in] hCamera ľ +/// \param [out] pimode ָ룬ģʽѡ񣬲ο@link #emSdkClrTmpMode @endlinkͶ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief The color temperature mode used when obtaining white balance. Refer to the function description section of @link #CameraSetClrTempMode @endlink. +/// \param [in] hCamera Camera handle. +/// \param [out] pimode pointer, return mode selection, reference @link #emSdkClrTmpMode @endlink type definition +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetClrTempMode( + CameraHandle hCamera, + int* pimode +); + +/// @ingroup API_COLOR +/// \~chinese +/// \brief ֶƽģʽ£øúһΰƽ⡣ЧʱΪյһ֡ͼʱ +/// \param [in] hCamera ľ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief In manual white balance mode, calling this function will perform a white balance. The effective time is when the next frame of image data is received. +/// \param [in] hCamera Camera handle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetOnceWB( + CameraHandle hCamera +); + +/// @ingroup API_COLOR +/// \~chinese +/// \brief ִһκƽҪֱ֧ܣ +/// \param [in] hCamera ľ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Performs a black balance operation. (Requires camera support for this feature) +/// \param [in] hCamera Camera handle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetOnceBB( + CameraHandle hCamera +); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief 趨ԶعĿֵ趨Χ[@link #tSdkExpose.uiTargetMin @endlink, @link #tSdkExpose.uiTargetMax @endlink] +/// \param [in] hCamera ľ +/// \param [in] iAeTarget Ŀֵ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Sets the brightness target for auto exposure. Setting range [@link #tSdkExpose.uiTargetMin @endlink, @link #tSdkExpose.uiTargetMax @endlink] +/// \param [in] hCamera Camera handle. +/// \param [in] iAeTarget Brightness target value. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetAeTarget( + CameraHandle hCamera, + int iAeTarget +); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief ԶعĿֵ +/// \param [in] hCamera ľ +/// \param [out] piAeTarget ָ룬Ŀֵ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the auto exposure's brightness target value. +/// \param [in] hCamera Camera handle. +/// \param [out] piAeTarget pointer, return target value. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetAeTarget( + CameraHandle hCamera, + int* piAeTarget +); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief 趨ԶعģʽعʱڷΧ +/// \param [in] hCamera ľ +/// \param [in] fMinExposureTime Сعʱ䣨΢룩 +/// \param [in] fMaxExposureTime عʱ䣨΢룩 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Setting the exposure time adjustment range of the automatic exposure mode +/// \param [in] hCamera Camera handle. +/// \param [in] fMinExposureTime Minimum exposure time (microseconds) +/// \param [in] fMaxExposureTime Maximum exposure time (microseconds) +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetAeExposureRange( + CameraHandle hCamera, + double fMinExposureTime, + double fMaxExposureTime + ); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief ԶعģʽعʱڷΧ +/// \param [in] hCamera ľ +/// \param [out] fMinExposureTime Сعʱ䣨΢룩 +/// \param [out] fMaxExposureTime عʱ䣨΢룩 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Exposure time adjustment range for automatic exposure mode +/// \param [in] hCamera Camera handle. +/// \param [out] fMinExposureTime Minimum exposure time (microseconds) +/// \param [out] fMaxExposureTime Maximum exposure time (microseconds) +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetAeExposureRange( + CameraHandle hCamera, + double* fMinExposureTime, + double* fMaxExposureTime + ); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief 趨ԶعģʽڷΧ +/// \param [in] hCamera ľ +/// \param [in] iMinAnalogGain С +/// \param [in] iMaxAnalogGain +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Setting the gain adjustment range of the automatic exposure mode +/// \param [in] hCamera Camera handle. +/// \param [in] iMinAnalogGain minimum gain +/// \param [in] iMaxAnalogGain maximum gain +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetAeAnalogGainRange( + CameraHandle hCamera, + int iMinAnalogGain, + int iMaxAnalogGain + ); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief ԶعģʽڷΧ +/// \param [in] hCamera ľ +/// \param [out] iMinAnalogGain С +/// \param [out] iMaxAnalogGain +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Gain adjustment range for automatic exposure mode +/// \param [in] hCamera Camera handle. +/// \param [out] iMinAnalogGain minimum gain +/// \param [out] iMaxAnalogGain maximum gain +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetAeAnalogGainRange( + CameraHandle hCamera, + int* iMinAnalogGain, + int* iMaxAnalogGain + ); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief Զعģʽĵֵ +/// \param [in] hCamera ľ +/// \param [in] iThreshold abs(Ŀ-ͼ) < iThreshold ֹͣԶ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the adjustment threshold for auto exposure mode +/// \param [in] hCamera Camera handle. +/// \param [in] iThreshold Stops automatic adjustment if abs (target brightness - image brightness) < iThreshold +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetAeThreshold( + CameraHandle hCamera, + int iThreshold + ); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief ȡԶعģʽĵֵ +/// \param [in] hCamera ľ +/// \param [out] iThreshold ȡĵֵ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get adjustment threshold for auto exposure mode +/// \param [in] hCamera Camera handle. +/// \param [out] iThreshold Read Threshold +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetAeThreshold( + CameraHandle hCamera, + int* iThreshold + ); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief عʱ䡣λΪ΢롣 +/// \param [in] hCamera ľ +/// \param [in] fExposureTime عʱ䣬λ΢롣 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note CMOSعĵλǰģˣعʱ䲢΢뼶ɵǻᰴȡᡣڵñ趨عʱ󣬽ٵ@link #CameraGetExposureTime @endlinkʵ趨ֵ +/// \~english +/// \brief Set the exposure time. The unit is microseconds. +/// \param [in] hCamera Camera handle. +/// \param [in] fExposureTime Exposure time in microseconds. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note For CMOS sensors, the unit of exposure is calculated in rows, so the exposure time cannot be continuously adjusted in microseconds. Instead, the entire line will be chosen. After calling this function to set the exposure time, it is recommended to call @link #CameraGetExposureTime @endlink to get the actual set value. +MVSDK_API CameraSdkStatus __stdcall CameraSetExposureTime( + CameraHandle hCamera, + double fExposureTime +); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief һеعʱ䡣 +/// \param [in] hCamera ľ +/// \param [out] pfLineTime ָ룬һеعʱ䣬λΪ΢롣 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note CMOSعĵλǰģˣعʱ䲢΢뼶ɵǻᰴȡᡣþǷCMOSعһжӦʱ䡣 +/// \~english +/// \brief Get a line of exposure time. +/// \param [in] hCamera Camera handle. +/// \param [out] pfLineTime returns the exposure time of one line in microseconds. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note For CMOS sensors, the unit of exposure is calculated in rows, so the exposure time cannot be continuously adjusted in microseconds. Instead, the entire line will be chosen. The function of this function is to return the CMOS camera exposure one line corresponding time. +MVSDK_API CameraSdkStatus __stdcall CameraGetExposureLineTime( + CameraHandle hCamera, + double* pfLineTime +); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief عʱ䡣 +/// \param [in] hCamera ľ +/// \param [out] pfExposureTime ָ룬صǰعʱ䣬λ΢롣 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \see CameraSetExposureTime +/// \~english +/// \brief Get camera exposure time. +/// \param [in] hCamera Camera handle. +/// \param [out] pfExposureTime returns the current exposure time in microseconds. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \see CameraSetExposureTime +MVSDK_API CameraSdkStatus __stdcall CameraGetExposureTime( + CameraHandle hCamera, + double* pfExposureTime +); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief عʱ䷶Χ +/// \param [in] hCamera ľ +/// \param [out] pfMin ָ룬عʱСֵλ΢롣 +/// \param [out] pfMax ָ룬عʱֵλ΢롣 +/// \param [out] pfStep ָ룬عʱIJֵλ΢롣 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get camera exposure time range +/// \param [in] hCamera Camera handle. +/// \param [out] pfMin Returns the minimum exposure time in microseconds. +/// \param [out] pfMax Returns the maximum exposure time in microseconds. +/// \param [out] pfStep Returns the exposure time in microseconds. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetExposureTimeRange( + CameraHandle hCamera, + double* pfMin, + double* pfMax, + double* pfStep + ); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief ͼģֵ +/// \param [in] hCamera ľ +/// \param [in] iAnalogGain 趨ģֵ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ֵ@link #tSdkExpose.fAnalogGainStep @endlink͵õʵʵͼźŷŴ +/// \~english +/// \brief Set the camera's image analog gain value. +/// \param [in] hCamera Camera handle. +/// \param [in] iAnalogGain gain value set +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note This value is multiplied by @link #tSdkExpose.fAnalogGainStep @endlink to get the actual image signal magnification. +MVSDK_API CameraSdkStatus __stdcall CameraSetAnalogGain( + CameraHandle hCamera, + INT iAnalogGain +); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief ͼźŵģֵ +/// \param [in] hCamera ľ +/// \param [out] piAnalogGain ָ룬صǰģֵ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \see CameraSetAnalogGain +/// \~english +/// \brief Obtain the analog gain value of the image signal. +/// \param [in] hCamera Camera handle. +/// \param [out] piAnalogGain Returns the current analog gain value. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \see CameraSetAnalogGain +MVSDK_API CameraSdkStatus __stdcall CameraGetAnalogGain( + CameraHandle hCamera, + INT* piAnalogGain +); + +/// @ingroup API_COLOR +/// \~chinese +/// \brief ͼ档 +/// \param [in] hCamera ľ +/// \param [in] iRGain ɫֵͨ +/// \param [in] iGGain ɫֵͨ +/// \param [in] iBGain ɫֵͨ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note 趨Χ@link #tRgbGainRange @endlinkԱʵʵķŴ趨ֵ/100 +/// \~english +/// \brief Set the digital gain of the image. +/// \param [in] hCamera Camera handle. +/// \param [in] iRGain The gain value of the red channel. +/// \param [in] iGGain Gain value of green channel. +/// \param [in] iBGain The gain value of the blue channel. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note The set scope is described by the @link #tRgbGainRange @endlink member. The actual magnification is the setting /100. +MVSDK_API CameraSdkStatus __stdcall CameraSetGain( + CameraHandle hCamera, + int iRGain, + int iGGain, + int iBGain +); + +/// @ingroup API_COLOR +/// \~chinese +/// \brief ͼ档 +/// \param [in] hCamera ľ +/// \param [out] piRGain ָ룬غɫֵͨ +/// \param [out] piGGain ָ룬ɫֵͨ +/// \param [out] piBGain ָ룬ɫֵͨ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \see CameraSetGain +/// \~english +/// \brief Get the digital gain of image processing. +/// \param [in] hCamera Camera handle. +/// \param [out] piRGain Returns the digital gain value of the red channel. +/// \param [out] piGGain Returns the digital gain value of the green channel. +/// \param [out] piBGain Returns the digital gain value of the blue channel. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \see CameraSetGain +MVSDK_API CameraSdkStatus __stdcall CameraGetGain( + CameraHandle hCamera, + int* piRGain, + int* piGGain, + int* piBGain +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief 趨LUT̬ģʽµGammaֵ +/// \param [in] hCamera ľ +/// \param [in] iGamma Ҫ趨Gammaֵ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note 趨ֵϱSDKڲֻеڶ̬ɵLUTģʽʱŻЧο@link #CameraSetLutMode @endlinkĺ˵֡ +/// \~english +/// \brief Set the gamma value in LUT dynamic generation mode. +/// \param [in] hCamera Camera handle. +/// \param [in] iGamma The gamma to be set. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note The set value will be stored in the SDK immediately, but it will only take effect when the camera is in LUT mode generated by dynamic parameters. Please refer to the function description part of @link #CameraSetLutMode @endlink. +MVSDK_API CameraSdkStatus __stdcall CameraSetGamma( + CameraHandle hCamera, + int iGamma +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief LUT̬ģʽµGammaֵ +/// \param [in] hCamera ľ +/// \param [out] piGamma ָ룬صǰGammaֵ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \see CameraSetGamma +/// \~english +/// \brief Get gamma value in LUT dynamic generation mode +/// \param [in] hCamera Camera handle. +/// \param [out] piGamma Returns the current gamma value. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \see CameraSetGamma +MVSDK_API CameraSdkStatus __stdcall CameraGetGamma( + CameraHandle hCamera, + int* piGamma +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief 趨LUT̬ģʽµĶԱȶֵ +/// \param [in] hCamera ľ +/// \param [in] iContrast 趨ĶԱȶֵ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note 趨ֵϱSDKڲֻеڶ̬ɵLUTģʽʱŻЧο@link #CameraSetLutMode @endlinkĺ˵֡ +/// \~english +/// \brief Sets the contrast value in LUT dynamic generation mode. +/// \param [in] hCamera Camera handle. +/// \param [in] iContrast Contrast value set by iContrast. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note The set value will be stored in the SDK immediately, but it will only take effect when the camera is in LUT mode generated by dynamic parameters. Please refer to the function description part of @link #CameraSetLutMode @endlink. +MVSDK_API CameraSdkStatus __stdcall CameraSetContrast( + CameraHandle hCamera, + int iContrast +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief LUT̬ģʽµĶԱȶֵ +/// \param [in] hCamera ľ +/// \param [out] piContrast ָ룬صǰĶԱȶֵ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \see CameraSetContrast +/// \~english +/// \brief Get the contrast value in LUT dynamic generation mode. +/// \param [in] hCamera Camera handle. +/// \param [out] piContrast Returns the current contrast value. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \see CameraSetContrast +MVSDK_API CameraSdkStatus __stdcall CameraGetContrast( + CameraHandle hCamera, + int* piContrast +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief 趨ͼıͶȡ +/// \param [in] hCamera ľ +/// \param [in] iSaturation 趨ıͶֵ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ԺڰЧ趨Χ@link #tSaturationRange @endlinká100ʾԭʼɫȣǿ +/// \~english +/// \brief Sets the saturation of image processing. +/// \param [in] hCamera Camera handle. +/// \param [in] iSaturation saturation value. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note is not valid for black and white cameras. The setting range is obtained by @link #tSaturationRange @endlink. 100 represents the original color and is not enhanced. +MVSDK_API CameraSdkStatus __stdcall CameraSetSaturation( + CameraHandle hCamera, + int iSaturation +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief ͼıͶȡ +/// \param [in] hCamera ľ +/// \param [out] piSaturation ָ룬صǰͼıͶֵ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \see CameraSetSaturation +/// \~english +/// \brief Get image processing saturation. +/// \param [in] hCamera Camera handle. +/// \param [out] piSaturation Returns the saturation value of the current image processing. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \see CameraSetSaturation +MVSDK_API CameraSdkStatus __stdcall CameraGetSaturation( + CameraHandle hCamera, + int* piSaturation +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief òɫתΪڰ׹ܵʹܡ +/// \param [in] hCamera ľ +/// \param [in] bEnable TRUEʾɫͼתΪڰס +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the color to mono function enable. +/// \param [in] hCamera Camera handle. +/// \param [in] bEnable TRUE to change the color image to black and white. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetMonochrome( + CameraHandle hCamera, + BOOL bEnable +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief òɫתڰ׹ܵʹ״ +/// \param [in] hCamera ľ +/// \param [out] pbEnable ָ롣TRUEʾ˲ɫͼתΪڰͼĹܡ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \see CameraSetMonochrome +/// \~english +/// \brief Get the status of enabling black and white color conversion. +/// \param [in] hCamera Camera handle. +/// \param [out] pbEnable Returns TRUE to enable the conversion of a color image to a mono image. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \see CameraSetMonochrome +MVSDK_API CameraSdkStatus __stdcall CameraGetMonochrome( + CameraHandle hCamera, + BOOL* pbEnable +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief òͼɫתܵʹܡ +/// \param [in] hCamera ľ +/// \param [in] bEnable TRUEʾͼɫתܣԻƽƬЧ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the enable for the color image color flip function. +/// \param [in] hCamera Camera handle. +/// \param [in] bEnable TRUE, means that the image color flip function is enabled, and the effect of similar film negatives can be obtained. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetInverse( + CameraHandle hCamera, + BOOL bEnable +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief ͼɫתܵʹ״̬ +/// \param [in] hCamera ľ +/// \param [out] pbEnable ָ룬ظùʹ״̬ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the status of the image color inversion function. +/// \param [in] hCamera Camera handle. +/// \param [out] pbEnable Returns this function enable state. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetInverse( + CameraHandle hCamera, + BOOL* pbEnable +); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief ԶعʱƵܵʹ״̬ +/// \param [in] hCamera ľ +/// \param [in] bEnable TRUEƵ;FALSEرոùܡ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ֶعģʽЧ +/// \~english +/// \brief Set the anti-strobe function's enable state during auto exposure. +/// \param [in] hCamera Camera handle. +/// \param [in] bEnable TRUE, enable anti-strobe function; FALSE, disable this function. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note Not valid for manual exposure mode. +MVSDK_API CameraSdkStatus __stdcall CameraSetAntiFlick( + CameraHandle hCamera, + BOOL bEnable +); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief ԶعʱƵܵʹ״̬ +/// \param [in] hCamera ľ +/// \param [out] pbEnable ָ룬ظùܵʹ״̬ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the anti-strobe function's enable state during auto exposure. +/// \param [in] hCamera Camera handle. +/// \param [out] pbEnable Returns the enable state of this function. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetAntiFlick( + CameraHandle hCamera, + BOOL* pbEnable +); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief ԶعʱƵƵѡ +/// \param [in] hCamera ľ +/// \param [out] piFrequencySel ָ룬ѡš0:50HZ 1:60HZ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief When the auto exposure is obtained, the frequency of the deflashing is selected. +/// \param [in] hCamera Camera handle. +/// \param [out] piFrequencySel Returns the selected index number. 0:50HZ 1:60HZ +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetLightFrequency( + CameraHandle hCamera, + int* piFrequencySel +); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief ԶعʱƵƵʡ +/// \param [in] hCamera ľ +/// \param [in] iFrequencySel 0:50HZ , 1:60HZ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Sets the frequency at which the flash disappears during auto exposure. +/// \param [in] hCamera Camera handle. +/// \param [in] iFrequencySel 0:50HZ , 1:60HZ +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetLightFrequency( + CameraHandle hCamera, + int iFrequencySel +); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief 趨ͼ֡ʡ +/// \param [in] hCamera ľ +/// \param [in] iFrameSpeed ѡ֡ģʽţΧ0tSdkCameraCapbility.iFrameSpeedDesc - 1 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Sets the frame rate of the camera output image. +/// \param [in] hCamera Camera handle. +/// \param [in] iFrameSpeed Frame rate index, ranging from 0 to tSdkCameraCapbility.iFrameSpeedDesc - 1 +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetFrameSpeed( + CameraHandle hCamera, + int iFrameSpeed +); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief ͼ֡ѡš +/// \param [in] hCamera ľ +/// \param [out] piFrameSpeed ѡ֡ģʽš +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \see CameraSetFrameSpeed +/// \~english +/// \brief Obtain the frame rate selection index number of the camera output image. +/// \param [in] hCamera Camera handle. +/// \param [out] piFrameSpeed Returns the selected frame rate mode index number. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \see CameraSetFrameSpeed +MVSDK_API CameraSdkStatus __stdcall CameraGetFrameSpeed( + CameraHandle hCamera, + int* piFrameSpeed +); + +/// @ingroup API_PARAMETERS +/// \~chinese +/// \brief 趨ȡĿ +/// \param [in] hCamera ľ +/// \param [in] iMode ȡĶ󡣲ο@link #emSdkParameterMode @endlink +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Sets the target object for parameter access. +/// \param [in] hCamera Camera handle. +/// \param [in] iMode The object accessed by the iMode parameter. Reference @link #emSdkParameterMode @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetParameterMode( + CameraHandle hCamera, + int iMode +); + +/// @ingroup API_PARAMETERS +/// \~chinese +/// \brief ȡȡĿ +/// \param [in] hCamera ľ +/// \param [out] piTarget زȡĶ󡣲ο@link #emSdkParameterMode @endlink +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Gets the target object for the parameter access. +/// \param [in] hCamera Camera handle. +/// \param [out] piTarget Returns the object accessed by the parameter. Reference @link #emSdkParameterMode @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetParameterMode( + CameraHandle hCamera, + int* piTarget +); + +/// @ingroup API_PARAMETERS +/// \~chinese +/// \brief òȡ롣غͱʱݸģǷػ߱档 +/// \param [in] hCamera ľ +/// \param [in] uMask 롣ο@link #emSdkPropSheetMask @endlink +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Sets the mask for parameter access. When the parameters are loaded and saved, the mask is used to determine whether each module parameter is loaded or saved. +/// \param [in] hCamera Camera handle. +/// \param [in] uMask mask. Reference @link #emSdkPropSheetMask @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetParameterMask( + CameraHandle hCamera, + UINT uMask +); + +/// @ingroup API_PARAMETERS +/// \~chinese +/// \brief 浱ǰָIJСṩA,B,C,Dռвı档 +/// \param [in] hCamera ľ +/// \param [in] iTeam 飬ο@link #emSdkParameterTeam @endlink +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Save current camera parameters to the specified parameter group. The camera provides A, B, C, D four sets of space for parameter preservation. +/// \param [in] hCamera Camera handle. +/// \param [in] iTeam parameter group, refer to @link #emSdkParameterTeam @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSaveParameter( + CameraHandle hCamera, + int iTeam +); + +/// @ingroup API_PARAMETERS +/// \~chinese +/// \brief 浱ǰָļСļԸƵĵϹأҲá +/// \param [in] hCamera ľ +/// \param [in] sFileName ļ· +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Saves the current camera parameters to the specified file. This file can be copied to another computer for loading by other cameras, or it can be used for parameter backup. +/// \param [in] hCamera Camera handle. +/// \param [in] sFileName Full path to the sFileName parameter file. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSaveParameterToFile( + CameraHandle hCamera, + char* sFileName +); + +/// @ingroup API_PARAMETERS +/// \~chinese +/// \brief PCָIJļмزҹ˾PCΪ.config׺ļλڰװµCamera\\ConfigsļС +/// \param [in] hCamera ľ +/// \param [in] sFileName ļ· +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Load parameters from the parameter file specified on the PC. Our camera parameters are saved on the PC as a .config suffix file, which is located in the Camera\\Configs folder under installation. +/// \param [in] hCamera Camera handle. +/// \param [in] sFileName Full path to the sFileName parameter file. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraReadParameterFromFile( + CameraHandle hCamera, + char* sFileName +); + +/// @ingroup API_PARAMETERS +/// \~chinese +/// \brief ָIJС +/// \param [in] hCamera ľ +/// \param [in] iTeam 飬ο@link #emSdkParameterTeam @endlink +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Loads the parameters of the specified group into the camera. +/// \param [in] hCamera Camera handle. +/// \param [in] iTeam parameter group, refer to @link #emSdkParameterTeam @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraLoadParameter( + CameraHandle hCamera, + int iTeam +); + +/// @ingroup API_PARAMETERS +/// \~chinese +/// \brief õǰѡIJ顣 +/// \param [in] hCamera ľ +/// \param [in] piTeam ָ룬صǰѡIJ顣 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the currently selected parameter group. +/// \param [in] hCamera Camera handle. +/// \param [in] piTeam Returns the currently selected parameter group. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetCurrentParameterGroup( + CameraHandle hCamera, + int* piTeam +); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief ͼݵķְС +/// \param [in] hCamera ľ +/// \param [in] iPackSel ְѡšְȿɻԽṹ@link #tSdkCameraCapbility.pPackLenDesc @endlinkԱ@link #tSdkCameraCapbility.iPackLenDesc @endlinkԱʾѡķְģʽ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ĿǰSDK汾УýӿڽGIGEӿЧ紫ķְС +/// \note ֧־֡ǽѡ8KķְСЧĽʹռõCPUʱ䡣 +/// \warning °汾SDKô˺SDKԶЭŵķְС +/// \~english +/// \brief Sets the packet size of the camera's transmitted image data. +/// \param [in] hCamera Camera handle. +/// \param [in] iPackSel Index number of the iPackSel packet length selection. The packet length can be expressed by the @link #tSdkCameraCapbility.pPackLenDesc @endlink member in the camera attribute structure. The @link #tSdkCameraCapbility.iPackLenDesc @endlink member represents the maximum number of optional packet modes. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note In the current SDK version, this interface is only valid for GIGE interface cameras and is used to control the packet size of the network transmission. +/// \note For NICs that support Jumbo Frames, we recommend choosing an 8K packet size that can effectively reduce the CPU processing time taken by the transfer. +/// \warning New version of the SDK does not need to call this function, the SDK will automatically negotiate the optimal packet size according to the network conditions +MVSDK_API CameraSdkStatus __stdcall CameraSetTransPackLen( + CameraHandle hCamera, + INT iPackSel +); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief ǰְСѡš +/// \param [in] hCamera ľ +/// \param [out] piPackSel ָ룬صǰѡķְСš +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \see CameraSetTransPackLen +/// \~english +/// \brief Gets the selected index number of the camera's current transmission packet size. +/// \param [in] hCamera Camera handle. +/// \param [out] piPackSel Returns the currently selected packet size index number. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \see CameraSetTransPackLen +MVSDK_API CameraSdkStatus __stdcall CameraGetTransPackLen( + CameraHandle hCamera, + INT* piPackSel +); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief Զعοڵʾ״̬ +/// \param [in] hCamera ľ +/// \param [out] pbIsVisible ָ룬TRUEʾǰڻᱻͼϡ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Gets the display status of the auto exposure reference window. +/// \param [in] hCamera Camera handle. +/// \param [out] pbIsVisible returns TRUE, indicating that the current window will be overlaid on the image content. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraIsAeWinVisible( + CameraHandle hCamera, + BOOL* pbIsVisible +); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief Զعοڵʾ״̬ +/// \param [in] hCamera ľ +/// \param [in] bIsVisible TRUEΪʾFALSEʾ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ô״̬Ϊʾ@link #CameraImageOverlay @endlinkܹλԾεķʽͼϡ +/// \~english +/// \brief Sets the display status of the auto exposure reference window. +/// \param [in] hCamera Camera handle. +/// \param [in] bIsVisible TRUE, set to show; FALSE, not show. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note When the window state is set to display, after calling @link #CameraImageOverlay @endlink, the window position can be superimposed on the image in a rectangular manner. +MVSDK_API CameraSdkStatus __stdcall CameraSetAeWinVisible( + CameraHandle hCamera, + BOOL bIsVisible +); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief Զعοڵλá +/// \param [in] hCamera ľ +/// \param [out] piHOff ָ룬شλϽǺֵ +/// \param [out] piVOff ָ룬شλϽֵ +/// \param [out] piWidth ָ룬شڵĿȡ +/// \param [out] piHeight ָ룬شڵĸ߶ȡ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the position of the auto exposure reference window. +/// \param [in] hCamera Camera handle. +/// \param [out] piHOff Returns the abscissa of the upper-left corner of the window. +/// \param [out] piVOff Returns the ordinate value in the upper left corner of the window. +/// \param [out] piWidth Returns the width of the window. +/// \param [out] piHeight Returns the height of the window. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetAeWindow( + CameraHandle hCamera, + INT* piHOff, + INT* piVOff, + INT* piWidth, + INT* piHeight +); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief ԶعIJοڡ +/// \param [in] hCamera ľ +/// \param [in] iHOff Ͻǵĺ +/// \param [in] iVOff Ͻǵ +/// \param [in] iWidth ڵĿ +/// \param [in] iHeight ڵĸ߶ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note iHOffiVOffiWidthiHeightȫΪ0򴰿Ϊÿֱµľ1/2Сŷֱʵı仯仯 +/// \note iHOffiVOffiWidthiHeightĴλ÷Χ˵ǰֱʷΧڣ Զʹþ1/2Сڡ +/// \~english +/// \brief Set the reference window for auto exposure. +/// \param [in] hCamera Camera handle. +/// \param [in] iHOff The horizontal axis of the window in the upper left corner +/// \param [in] iVOff The ordinate of the top left corner of the window +/// \param [in] iWidth width of window +/// \param [in] iHeight Height of window +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note If iHOff, iVOff, iWidth, and iHeight are all 0, the window is set to the center 1/2 size for each resolution. It can follow changes as the resolution changes. +/// \note If the window position range determined by iHOff, iVOff, iWidth, and iHeight exceeds the current resolution range, the centered 1/2 size window is automatically used. +MVSDK_API CameraSdkStatus __stdcall CameraSetAeWindow( + CameraHandle hCamera, + int iHOff, + int iVOff, + int iWidth, + int iHeight +); + +/// @ingroup API_MIRROR +/// \~chinese +/// \brief ͼΪˮƽʹֱ +/// \param [in] hCamera ľ +/// \param [in] iDir ʾķ0ʾˮƽ1ʾֱ +/// \param [in] bEnable TRUEʹܾ;FALSEֹ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set image mirroring operation. The mirroring operation is divided into horizontal and vertical directions. +/// \param [in] hCamera Camera handle. +/// \param [in] iDir Indicates the direction of the mirror. 0 means horizontal direction; 1 means vertical direction. +/// \param [in] bEnable TRUE to enable mirroring; FALSE to disable mirroring +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetMirror( + CameraHandle hCamera, + int iDir, + BOOL bEnable +); + +/// @ingroup API_MIRROR +/// \~chinese +/// \brief ͼľ״̬ +/// \param [in] hCamera ľ +/// \param [in] iDir ʾҪõľ0ʾˮƽ1ʾֱ +/// \param [out] pbEnable ָ룬TRUEʾiDirָķʹܡ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the mirrored state of the image. +/// \param [in] hCamera Camera handle. +/// \param [in] iDir Indicates the mirroring direction to be obtained. 0 means horizontal direction; 1 means vertical direction. +/// \param [out] pbEnable Returns TRUE, indicating that the direction mirror image of iDir is enabled. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetMirror( + CameraHandle hCamera, + int iDir, + BOOL* pbEnable +); + +/// @ingroup API_MIRROR +/// \~chinese +/// \brief ͼת +/// \param [in] hCamera ľ +/// \param [in] iRot ʾתĽǶȣʱ뷽򣩣0ת 1:90 2:180 3:270ȣ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set image rotation operation +/// \param [in] hCamera Camera handle. +/// \param [in] iRot rotation angle (counterclockwise) (0: no rotation 1:90 degrees 2:180 degrees 3:270 degrees) +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetRotate( + CameraHandle hCamera, + int iRot + ); + +/// @ingroup API_MIRROR +/// \~chinese +/// \brief ͼת״̬ +/// \param [in] hCamera ľ +/// \param [out] iRot ʾҪõת򡣣ʱ뷽򣩣0ת 1:90 2:180 3:270ȣ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the rotation state of the image. +/// \param [in] hCamera Camera handle. +/// \param [out] iRot Indicates the direction of rotation to get. (Counterclockwise) (0: Do not rotate 1:90 degree 2: 180 degree 3: 270 degree) +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetRotate( + CameraHandle hCamera, + int* iRot + ); + +/// @ingroup API_COLOR +/// \~chinese +/// \brief ðƽοڵλá +/// \param [in] hCamera ľ +/// \param [out] PiHOff ָ룬زοڵϽǺ +/// \param [out] PiVOff ָ룬زοڵϽ +/// \param [out] PiWidth ָ룬زοڵĿȡ +/// \param [out] PiHeight ָ룬زοڵĸ߶ȡ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the position of the white balance reference window. +/// \param [in] hCamera Camera handle. +/// \param [out] PiHOff Returns the top-left abscissa of the reference window. +/// \param [out] PiVOff Returns the upper-left ordinate of the reference window. +/// \param [out] PiWidth Returns the width of the reference window. +/// \param [out] PiHeight Returns the height of the reference window. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetWbWindow( + CameraHandle hCamera, + INT* PiHOff, + INT* PiVOff, + INT* PiWidth, + INT* PiHeight +); + +/// @ingroup API_COLOR +/// \~chinese +/// \brief ðƽοڵλá +/// \param [in] hCamera ľ +/// \param [in] iHOff οڵϽǺꡣ +/// \param [in] iVOff οڵϽꡣ +/// \param [in] iWidth οڵĿȡ +/// \param [in] iHeight οڵĸ߶ȡ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Sets the position of the white balance reference window. +/// \param [in] hCamera Camera handle. +/// \param [in] iHOff The upper left corner of the reference window. +/// \param [in] iVOff The upper left ordinate of the reference window. +/// \param [in] iWidth Width of the reference window. +/// \param [in] iHeight The height of the reference window. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetWbWindow( + CameraHandle hCamera, + INT iHOff, + INT iVOff, + INT iWidth, + INT iHeight +); + +/// @ingroup API_COLOR +/// \~chinese +/// \brief ðƽⴰڵʾ״̬ +/// \param [in] hCamera ľ +/// \param [out] pbShow ָ룬TRUEʾǿɼġ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the display status of the white balance window. +/// \param [in] hCamera Camera handle. +/// \param [out] pbShow returns TRUE, indicating that the window is visible. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraIsWbWinVisible( + CameraHandle hCamera, + BOOL* pbShow +); + +/// @ingroup API_COLOR +/// \~chinese +/// \brief ðƽⴰڵʾ״̬ +/// \param [in] hCamera ľ +/// \param [in] bShow TRUEʾΪɼ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ڵ@link #CameraImageOverlay @endlinkͼϽԾεķʽӰƽοڵλá +/// \~english +/// \brief Sets the display status of the white balance window. +/// \param [in] hCamera Camera handle. +/// \param [in] bShow TRUE indicates that the setting is visible. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note After calling @link #CameraImageOverlay @endlink, the white balance reference window's position will be overlaid on the image content in a rectangular manner. +MVSDK_API CameraSdkStatus __stdcall CameraSetWbWinVisible( + CameraHandle hCamera, + BOOL bShow +); + +/// @ingroup API_ISP +/// \~chinese +/// \brief ͼϵʮߡƽοڡԶعοڵͼΡֻΪɼ״̬ʮߺͲοڲܱϡ +/// \param [in] hCamera ľ +/// \param [in] pRgbBuffer ͼݻ +/// \param [in] pFrInfo ͼ֡ͷϢ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief The cross-line, white balance reference window, auto exposure reference window, etc. are superimposed on the input image data. Only crosshairs and reference windows that are set to visible can be overlaid. +/// \param [in] hCamera Camera handle. +/// \param [in] pRgbBuffer image data buffer. +/// \param [in] pFrInfo Frame header information for the image. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImageOverlay( + CameraHandle hCamera, + BYTE* pRgbBuffer, + tSdkFrameHead* pFrInfo +); + +/// @ingroup API_UTIL +/// \~chinese +/// \brief ָʮߵIJ +/// \param [in] hCamera ľ +/// \param [in] iLine ʾҪõڼʮߵ״̬ΧΪ[0,8]9 +/// \param [in] x ʮλõĺֵ +/// \param [in] y ʮλõֵ +/// \param [in] uColor ʮߵɫʽΪ(R|(G<<8)|(B<<16)) +/// \param [in] bVisible ʮߵʾ״̬TRUEʾʾ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ֻΪʾ״̬ʮߣڵ@link #CameraImageOverlay @endlinkŻᱻӵͼϡ +/// \~english +/// \brief Set the parameters for the specified crosshairs. +/// \param [in] hCamera Camera handle. +/// \param [in] iLine Indicates the status of the first few crosshairs. The range is [0,8] for a total of 9. +/// \param [in] x The abscissa of the crosshair center position. +/// \param [in] y The y-axis value of the crosshair center position. +/// \param [in] uColor The color of the crosshair in the format (R|(G<<8)|(B<<16)) +/// \param [in] bVisible Crosshair display status. TRUE, indicates the display. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note Only crosshairs set to display state will be superimposed on the image after calling @link #CameraImageOverlay @endlink. +MVSDK_API CameraSdkStatus __stdcall CameraSetCrossLine( + CameraHandle hCamera, + int iLine, + INT x, + INT y, + UINT uColor, + BOOL bVisible +); + +/// @ingroup API_UTIL +/// \~chinese +/// \brief ָʮߵ״̬ +/// \param [in] hCamera ľ +/// \param [in] iLine ʾҪȡĵڼʮߵ״̬ΧΪ[0,8]9 +/// \param [out] px ָ룬ظʮλõĺꡣ +/// \param [out] py ָ룬ظʮλõĺꡣ +/// \param [out] pcolor ָ룬ظʮߵɫʽΪ(R|(G<<8)|(B<<16)) +/// \param [out] pbVisible ָ룬TRUEʾʮ߿ɼ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the status of the designated crosshairs. +/// \param [in] hCamera Camera handle. +/// \param [in] iLine Indicates the status of the first few crosshairs to get. The range is [0,8] for a total of 9. +/// \param [out] px Returns the abscissa of the center of the crosshair. +/// \param [out] py Returns the abscissa of the center of the crosshair. +/// \param [out] pcolor Returns the color of this crosshair in the format (R|(G<<8)|(B<<16)). +/// \param [out] pbVisible returns TRUE, indicating that the crosshairs are visible. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetCrossLine( + CameraHandle hCamera, + INT iLine, + INT* px, + INT* py, + UINT* pcolor, + BOOL* pbVisible +); + +/// @ingroup API_BASIC +/// \~chinese +/// \brief ṹ塣ýṹаõĸֲķΧϢغIJأҲڶ̬ý档 +/// \param [in] hCamera ľ +/// \param [out] pCameraInfo ָ룬ظĽṹ塣 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the camera's characteristic description structure. This structure contains range information of various parameters that the camera can set. Determines the return of parameters for related functions and can also be used to dynamically create camera configuration interfaces. +/// \param [in] hCamera Camera handle. +/// \param [out] pCameraInfo Returns the structure of the camera's property description. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetCapability( + CameraHandle hCamera, + tSdkCameraCapbility* pCameraInfo +); + +/******************************************************/ +// : CameraGetCapabilityEx +// : ṹ塣ýṹа +// õĸֲķΧϢغIJ +// أҲڶ̬ý档 +// : sDeviceModel ͺţɨблȡ +// pCameraInfo ָ룬ظĽṹ塣 +// tSdkCameraCapbilityCameraDefine.hж塣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +MVSDK_API CameraSdkStatus __stdcall CameraGetCapabilityEx( + char* sDeviceModel, + tSdkCameraCapbility* pCameraInfo, + PVOID hCameraHandle +); + +/// @ingroup API_USERDATA +/// \~chinese +/// \brief кš +/// \param [in] hCamera ľ +/// \param [in] pbySN кŵĻ +/// \param [in] iLevel Ҫ趨кżֻ12 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ҹ˾кŷΪ30ҹ˾ԶкţʱѾ趨޷޸ģ12οʹáÿкųȶ32ֽڡ +/// \~english +/// \brief Set the camera's serial number. +/// \param [in] hCamera Camera handle. +/// \param [in] pbySN The buffer for the serial number. +/// \param [in] iLevel The serial number to be set can only be 1 or 2. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note Our company camera serial number is divided into 3 levels. Level 0 is our company's custom camera serial number, which has been set at the factory and cannot be modified. Levels 1 and 2 are reserved for secondary development. Each serial number length is 32 bytes. +MVSDK_API CameraSdkStatus __stdcall CameraWriteSN( + CameraHandle hCamera, + BYTE* pbySN, + INT iLevel +); + +/// @ingroup API_USERDATA +/// \~chinese +/// \brief ȡָкš +/// \param [in] hCamera ľ +/// \param [in] pbySN кŵĻ +/// \param [in] iLevel Ҫȡкż𡣿Ϊ012 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \see CameraWriteSN +/// \~english +/// \brief Reads the camera's assigned level serial number. +/// \param [in] hCamera Camera handle. +/// \param [in] pbySN The buffer for the serial number. +/// \param [in] iLevel The sequence number to read. Can be 0, 1 and 2. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \see CameraWriteSN +MVSDK_API CameraSdkStatus __stdcall CameraReadSN( + CameraHandle hCamera, + BYTE* pbySN, + INT iLevel +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief ӲģʽµĴʱʱ䣬λ΢롣 +/// \param [in] hCamera ľ +/// \param [in] uDelayTimeUs Ӳʱλ΢롣 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note Ӳźٺ󣬾ָʱٿʼɼͼ +/// \~english +/// \brief Set the trigger delay time in hardware trigger mode, in microseconds. +/// \param [in] hCamera Camera handle. +/// \param [in] uDelayTimeUs Hard trigger delay. Units microseconds. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note When the hard trigger signal arrives, after a specified delay, it begins to capture the image. +MVSDK_API CameraSdkStatus __stdcall CameraSetTriggerDelayTime( + CameraHandle hCamera, + UINT uDelayTimeUs +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief õǰ趨Ӳʱʱ䡣 +/// \param [in] hCamera ľ +/// \param [out] puDelayTimeUs ָ룬ʱʱ䣬λ΢롣 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the currently set hard trigger delay time. +/// \param [in] hCamera Camera handle. +/// \param [out] puDelayTimeUs Returns the delay time in microseconds. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetTriggerDelayTime( + CameraHandle hCamera, + UINT* puDelayTimeUs +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief ôģʽµĴ֡ӲģʽЧĬΪ1֡һδźŲɼһ֡ͼ +/// \param [in] hCamera ľ +/// \param [in] iCount һδɼ֡ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Sets the number of trigger frames in the trigger mode. Valid for both software and hardware trigger modes. The default is 1 frame, that is, one trigger signal captures a frame of image. +/// \param [in] hCamera Camera handle. +/// \param [in] iCount The number of frames triggered at a time. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetTriggerCount( + CameraHandle hCamera, + INT iCount +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief һδ֡ +/// \param [in] hCamera ľ +/// \param [out] piCount һδźŲɼ֡ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the number of trigger frames. +/// \param [in] hCamera Camera handle. +/// \param [out] piCount The number of frames to trigger signal acquisition at one time. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetTriggerCount( + CameraHandle hCamera, + INT* piCount +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief ִһִк󣬻ᴥ@link #CameraSetTriggerCount @endlinkָ֡ +/// \param [in] hCamera ľ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \see CameraSetTriggerMode +/// \~english +/// \brief Perform a soft trigger. After execution, the number of frames specified by @link #CameraSetTriggerCount @endlink is triggered. +/// \param [in] hCamera Camera handle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \see CameraSetTriggerMode +MVSDK_API CameraSdkStatus __stdcall CameraSoftTrigger( + CameraHandle hCamera +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief Ĵģʽ +/// \param [in] hCamera ľ +/// \param [in] iModeSel ģʽѡš0ʾɼģʽ1ʾģʽ2ʾӲģʽ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the camera's trigger mode. +/// \param [in] hCamera Camera handle. +/// \param [in] iModeSel mode selects the index number. 0 means continuous acquisition mode; 1 means software trigger mode; 2 means hardware trigger mode. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetTriggerMode( + CameraHandle hCamera, + int iModeSel +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief Ĵģʽ +/// \param [in] hCamera ľ +/// \param [out] piModeSel ָ룬صǰѡģʽš +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the camera's trigger mode. +/// \param [in] hCamera Camera handle. +/// \param [out] piModeSel Returns the index of the currently selected camera trigger mode. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetTriggerMode( + CameraHandle hCamera, + INT* piModeSel +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief IOŶϵSTROBEźšźſƿƣҲⲿеſơ +/// \param [in] hCamera ľ +/// \param [in] iMode ģʽο@link #emStrobeControl @endlink +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the STROBE signal on the IO pin terminal. This signal can be used for flash control or external mechanical shutter control. +/// \param [in] hCamera Camera handle. +/// \param [in] iMode strobe mode, refer to @link #emStrobeControl @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetStrobeMode( + CameraHandle hCamera, + INT iMode +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief ȡǰSTROBEźõģʽ +/// \param [in] hCamera ľ +/// \param [out] piMode ģʽ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Gets the mode of the current STROBE signal setting. +/// \param [in] hCamera Camera handle. +/// \param [out] piMode Return Mode +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetStrobeMode( + CameraHandle hCamera, + INT* piMode +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief STROBEźŴSTROBE_SYNC_WITH_TRIGʱͨúԴźʱʱ䡣 +/// \param [in] hCamera ľ +/// \param [in] uDelayTimeUs Դźŵʱʱ䣬λΪusΪ0Ϊ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief When the STROBE signal is in STROBE_SYNC_WITH_TRIG, set its relative trigger signal delay time by this function. +/// \param [in] hCamera Camera handle. +/// \param [in] uDelayTimeUs Delay time relative to the trigger signal, in units of us. Can be 0, but it cannot be negative. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetStrobeDelayTime( + CameraHandle hCamera, + UINT uDelayTimeUs +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief STROBEźŴSTROBE_SYNC_WITH_TRIGʱͨúԴźʱʱ䡣 +/// \param [in] hCamera ľ +/// \param [out] upDelayTimeUs ָ룬ʱʱ䣬λus +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief When the STROBE signal is in STROBE_SYNC_WITH_TRIG, the relative trigger signal delay time is obtained through this function. +/// \param [in] hCamera Camera handle. +/// \param [out] upDelayTimeUs Returns the delay time in us. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetStrobeDelayTime( + CameraHandle hCamera, + UINT* upDelayTimeUs +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief STROBEźŴSTROBE_SYNC_WITH_TRIGʱͨúȡ +/// \param [in] hCamera ľ +/// \param [in] uTimeUs ĿȣλΪʱus +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief When the STROBE signal is in STROBE_SYNC_WITH_TRIG, set its pulse width by this function. +/// \param [in] hCamera Camera handle. +/// \param [in] uTimeUs The width of the pulse in units of time us. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetStrobePulseWidth( + CameraHandle hCamera, + UINT uTimeUs +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief STROBEźŴSTROBE_SYNC_WITH_TRIGʱͨúȡ +/// \param [in] hCamera ľ +/// \param [out] upTimeUs ָ룬ȡλΪus +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief When the STROBE signal is at STROBE_SYNC_WITH_TRIG, its pulse width is obtained by this function. +/// \param [in] hCamera Camera handle. +/// \param [out] upTimeUs Returns the pulse width. The unit is us. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetStrobePulseWidth( + CameraHandle hCamera, + UINT* upTimeUs +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief STROBEźŴSTROBE_SYNC_WITH_TRIGʱͨúЧƽļԡĬΪЧźŵʱSTROBEźűߡ +/// \param [in] hCamera ľ +/// \param [in] uPolarity STROBEźŵļԣ0Ϊ͵ƽЧ1ΪߵƽЧĬΪߵƽЧ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief When the STROBE signal is at STROBE_SYNC_WITH_TRIG, the polarity of its active level is set by this function. The default is high active. When the trigger signal arrives, the STROBE signal is pulled high. +/// \param [in] hCamera Camera handle. +/// \param [in] uPolarity Polarity of STROBE signal, 0 is active low and 1 is active high. The default is active high. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetStrobePolarity( + CameraHandle hCamera, + INT uPolarity +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief ǰSTROBEźŵЧԡĬΪߵƽЧ +/// \param [in] hCamera ľ +/// \param [in] upPolarity ָ룬STROBEźŵǰЧԡ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Obtain the effective polarity of the camera's current STROBE signal. The default is active high. +/// \param [in] hCamera Camera handle. +/// \param [in] upPolarity Returns the current effective polarity of the STROBE signal. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetStrobePolarity( + CameraHandle hCamera, + INT* upPolarity +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief ⴥźŵࡣϱء±ء߸ߡ͵ƽʽ +/// \param [in] hCamera ľ +/// \param [in] iType ⴥź࣬ο@link #emExtTrigSignal @endlink +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the type of trigger signal outside the camera. Upper edge, lower edge, or high and low level. +/// \param [in] hCamera Camera handle. +/// \param [in] iType External trigger signal type, refer to @link #emExtTrigSignal @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetExtTrigSignalType( + CameraHandle hCamera, + INT iType +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief ǰⴥźŵࡣ +/// \param [in] hCamera ľ +/// \param [out] ipType ָ룬ⴥź࣬ο@link #emExtTrigSignal @endlink +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the type of camera's current external trigger signal. +/// \param [in] hCamera Camera handle. +/// \param [out] ipType Returns the type of external trigger signal, see @link #emExtTrigSignal @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetExtTrigSignalType( + CameraHandle hCamera, + INT* ipType +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief ⴥģʽ£ŵķʽĬΪ׼ŷʽֹŵCMOS֧GRRʽ +/// \param [in] hCamera ľ +/// \param [in] iType ⴥŷʽο@link #emExtTrigShutterMode @endlink +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief In the external trigger mode, the camera shutter mode defaults to the standard shutter mode. Part of the rolling shutter CMOS camera supports GRR mode. +/// \param [in] hCamera Camera handle. +/// \param [in] iType triggers the shutter. Reference @link #emExtTrigShutterMode @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetExtTrigShutterType( + CameraHandle hCamera, + INT iType +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief ⴥģʽ£ŵķʽ +/// \param [in] hCamera ľ +/// \param [out] ipType ָ룬صǰ趨ⴥŷʽ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \see CameraSetExtTrigShutterType +/// \~english +/// \brief Get the camera shutter mode in external trigger mode +/// \param [in] hCamera Camera handle. +/// \param [out] ipType Returns the currently set external trigger shutter mode. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \see CameraSetExtTrigShutterType +MVSDK_API CameraSdkStatus __stdcall CameraGetExtTrigShutterType( + CameraHandle hCamera, + INT* ipType +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief ⴥźʱʱ䣬ĬΪ0λΪ΢롣 +/// \param [in] hCamera ľ +/// \param [in] uDelayTimeUs ʱʱ䣬λΪ΢룬ĬΪ0. +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the delay time of external trigger signal. The default is 0 and the unit is microsecond. +/// \param [in] hCamera Camera handle. +/// \param [in] uDelayTimeUs Delay time in microseconds. Default is 0. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetExtTrigDelayTime( + CameraHandle hCamera, + UINT uDelayTimeUs +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief õⴥźʱʱ䣬ĬΪ0λΪ΢롣 +/// \param [in] hCamera ľ +/// \param [out] upDelayTimeUs ʱ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the set external trigger signal delay time, the default is 0, the unit is microseconds. +/// \param [in] hCamera Camera handle. +/// \param [out] upDelayTimeUs trigger delay +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetExtTrigDelayTime( + CameraHandle hCamera, + UINT* upDelayTimeUs +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief ⴥźŵʱ䣬ֻеⴥźģʽѡߵƽߵ͵ƽʱȥʱŻЧĬΪ0λΪ΢롣 +/// \param [in] hCamera ľ +/// \param [in] uTimeUs ʱ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Sets the debouncing time of the trigger signal outside the camera. The debounce time will only take effect when the external trigger signal mode selects high or low trigger. The default is 0 and the unit is microseconds. +/// \param [in] hCamera Camera handle. +/// \param [in] uTimeUs time +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetExtTrigJitterTime( + CameraHandle hCamera, + UINT uTimeUs +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief õⴥʱ䣬ĬΪ0.λΪ΢롣 +/// \param [in] hCamera ľ +/// \param [out] upTimeUs ʱ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the set camera trigger debounce time, the default is 0. The unit is microseconds. +/// \param [in] hCamera Camera handle. +/// \param [out] upTimeUs time +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetExtTrigJitterTime( + CameraHandle hCamera, + UINT* upTimeUs +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief ⴥ +/// \param [in] hCamera ľ +/// \param [out] puCapabilityMask ָ룬ظⴥ룬οCameraDefine.hEXT_TRIG_MASK_ ͷĺ궨塣 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the triggering attribute mask outside the camera +/// \param [in] hCamera Camera handle. +/// \param [out] puCapabilityMask Returns the mask of the camera's triggering property, masked by the macro definition at the beginning of EXT_TRIG_MASK_ in CameraDefine.h. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetExtTrigCapability( + CameraHandle hCamera, + UINT* puCapabilityMask +); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief ⴥźΪƽģʽʱʱֱֹͣƽź +/// \param [in] hCamera ľ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief When the external trigger signal is in level mode, it temporarily stops triggering the camera until the level signal jumps and continues to trigger. +/// \param [in] hCamera Camera handle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraPauseLevelTrigger( + CameraHandle hCamera + ); + +/// @ingroup API_ROI +/// \~chinese +/// \brief ץģʽµķֱѡš +/// \param [in] hCamera ľ +/// \param [out] pImageResolution ָ룬ץģʽķֱʡ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the resolution selection index number in snap mode. +/// \param [in] hCamera Camera handle. +/// \param [out] pImageResolution Pointer to return the resolution of the snap mode. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetResolutionForSnap( + CameraHandle hCamera, + tSdkImageResolution* pImageResolution +); + +/// @ingroup API_ROI +/// \~chinese +/// \brief ץģʽͼķֱʡ +/// \param [in] hCamera ľ +/// \param [in] pImageResolution ֱ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note pImageResolution->iWidth = pImageResolution->iHeight = 0ʾ趨Ϊ浱ǰԤֱʡץĵͼķֱʻ͵ǰ趨Ԥֱһ +/// \~english +/// \brief Sets the resolution of the camera's output image in snap shot mode. +/// \param [in] hCamera Camera handle. +/// \param [in] pImageResolution Resolution +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note If pImageResolution->iWidth = pImageResolution->iHeight = 0, then it is set to follow the current preview resolution. The resolution of the captured image will be the same as the currently set preview resolution. +MVSDK_API CameraSdkStatus __stdcall CameraSetResolutionForSnap( + CameraHandle hCamera, + tSdkImageResolution* pImageResolution +); + +/// @ingroup API_ROI +/// \~chinese +/// \brief 򿪷ֱԶ壬ͨӻķʽһԶֱʡ +/// \param [in] hCamera ľ +/// \param [out] pImageCustom ָ룬Զķֱʡ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Open the resolution custom panel and configure a custom resolution visually. +/// \param [in] hCamera Camera handle. +/// \param [out] pImageCustom Returns the custom resolution. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraCustomizeResolution( + CameraHandle hCamera, + tSdkImageResolution* pImageCustom +); + +/// @ingroup API_UTIL +/// \~chinese +/// \brief 򿪲οԶ塣ͨӻķʽһԶ崰ڵλáһԶƽԶعIJοڡ +/// \param [in] hCamera ľ +/// \param [in] iWinType ҪɵIJοڵ;0:Զعοڣ1:ƽοڡ +/// \param [in] hParent øúĴڵľΪNULL +/// \param [out] piHOff ָ룬Զ崰ڵϽǺꡣ +/// \param [out] piVOff ָ룬Զ崰ڵϽꡣ +/// \param [out] piWidth ָ룬Զ崰ڵĿȡ +/// \param [out] piHeight ָ룬Զ崰ڵĸ߶ȡ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Open the reference window custom panel. And through a visual way to get a custom window location. It is generally a reference window with custom white balance and auto exposure. +/// \param [in] hCamera Camera handle. +/// \param [in] iWinType Purpose of the reference window to be generated. 0: Auto exposure reference window; 1: White balance reference window. +/// \param [in] hParent The handle of the window that called the function. Can be NULL. +/// \param [out] piHOff Returns the upper left-hand abscissa of the custom window. +/// \param [out] piVOff Returns the upper left ordinate of the custom window. +/// \param [out] piWidth Returns the width of the custom window. +/// \param [out] piHeight Returns the height of the custom window. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraCustomizeReferWin( + CameraHandle hCamera, + INT iWinType, + HWND hParent, + INT* piHOff, + INT* piVOff, + INT* piWidth, + INT* piHeight +); + +/// @ingroup API_SETTINGS_PAGE +/// \~chinese +/// \brief ôʾ״̬ +/// \param [in] hCamera ľ +/// \param [in] bShow TRUEʾ;FALSEء +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ȵ@link #CameraCreateSettingPage @endlinkɹôں󣬲ܵñʾ +/// \~english +/// \brief Set the camera property configuration window display status. +/// \param [in] hCamera Camera handle. +/// \param [in] bShow TRUE, show; FALSE, hide. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note You must call @link #CameraCreateSettingPage @endlink successfully to create the camera property configuration window before calling this function to display. +MVSDK_API CameraSdkStatus __stdcall CameraShowSettingPage( + CameraHandle hCamera, + BOOL bShow +); + +/// @ingroup API_SETTINGS_PAGE +/// \~chinese +/// \brief ôڡøúSDKڲôڣʡȥ¿ýʱ䡣ǿҽʹʹøúSDKΪôڡ +/// \param [in] hCamera ľ +/// \param [in] hParent ӦóڵľΪNULL +/// \param [in] pWinText ַָ룬ʾı +/// \param [in] pCallbackFunc ϢĻصӦ¼ʱpCallbackFuncָĺᱻ +/// \param [in] pCallbackCtx صĸӲΪNULL +/// \param [in] uReserved ԤΪ0 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Create the camera's property configuration window. Call this function, the SDK will help you create a camera configuration window, eliminating the need to redevelop the camera configuration interface. It is strongly recommended that you use this function to have the SDK create a configuration window for you. +/// \param [in] hCamera Camera handle. +/// \param [in] hParent Handle to the main window of the application. Can be NULL. +/// \param [in] pWinText string pointer, window title bar. +/// \param [in] pCallbackFunc Callback function of window message. The function pointed to by pCallbackFunc will be called when the corresponding event occurs. +/// \param [in] pCallbackCtx Additional parameters for the callback function. Can be NULL. +/// \param [in] uReserved Reserved. Must be set to 0. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraCreateSettingPage( + CameraHandle hCamera, + HWND hParent, + char* pWinText, + CAMERA_PAGE_MSG_PROC pCallbackFunc, + PVOID pCallbackCtx, + UINT uReserved +); + +/// @ingroup API_SETTINGS_PAGE +/// \~chinese +/// \brief ʹĬϲôڡ +/// \param [in] hCamera ľ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Use the default parameters to create the camera's property configuration window. +/// \param [in] hCamera Camera handle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraCreateSettingPageEx( + CameraHandle hCamera +); + +/// @ingroup API_SETTINGS_PAGE +/// \~chinese +/// \brief ôڵļҳ档ôжҳ湹ɣú趨ǰһҳΪ״̬ʾǰˡ +/// \param [in] hCamera ľ +/// \param [in] index ҳšο@link #emSdkPropSheetMask @endlink +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Sets the camera configuration window's activation page. The camera configuration window is composed of multiple sub-pages. This function can set which sub-page is currently active and displayed at the forefront. +/// \param [in] hCamera Camera handle. +/// \param [in] index The index number of the subpage. Reference @link #emSdkPropSheetMask @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetActiveSettingSubPage( + CameraHandle hCamera, + INT index +); + +/// @ingroup API_SETTINGS_PAGE +/// \~chinese +/// \brief ҳΪӴڷ񣬲ָĸڡ +/// \param [in] hCamera ľ +/// \param [in] hParentWnd ھΪNULL(0)ָҳΪڡ +/// \param [in] Flags ܱ־λbit0: رbit1-31: (Ϊ0) +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Sets the camera configuration page to child window style and specifies its parent window. +/// \param [in] hCamera Camera handle. +/// \param [in] hParentWnd The parent window handle, NULL (0) restores the configuration page to a popup window. +/// \param [in] Flags function flag, bit0: Hide title bar, bit1-31: Reserved (must be 0) +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetSettingPageParent( + CameraHandle hCamera, + HWND hParentWnd, + DWORD Flags + ); + +/// @ingroup API_SETTINGS_PAGE +/// \~chinese +/// \brief ȡҳĴھ +/// \param [in] hCamera ľ +/// \param [out] hWnd ҳĴھ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Gets the window handle of the camera configuration page. +/// \param [in] hCamera Camera handle. +/// \param [out] hWnd Returns the window handle of the configuration page. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetSettingPageHWnd( + CameraHandle hCamera, + HWND* hWnd + ); + +MVSDK_API CameraSdkStatus __stdcall CameraSpecialControl( + CameraHandle hCamera, + DWORD dwCtrlCode, + DWORD dwParam, + LPVOID lpData +); + +/// @ingroup API_BASIC +/// \~chinese +/// \brief ֡ʵͳϢ֡Ͷ֡ +/// \param [in] hCamera ľ +/// \param [out] psFrameStatistic ָ룬ͳϢ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the frame rate statistics of the camera, including error frame and frame loss. +/// \param [in] hCamera Camera handle. +/// \param [out] psFrameStatistic Returns statistics. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetFrameStatistic( + CameraHandle hCamera, + tSdkFrameStatistic* psFrameStatistic +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief ͼģʹ״̬ +/// \param [in] hCamera ľ +/// \param [in] bEnable TRUEʹܣFALSEֹ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the enable status of the image noise reduction module. +/// \param [in] hCamera Camera handle. +/// \param [in] bEnable TRUE, enable; FALSE, disable. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetNoiseFilter( + CameraHandle hCamera, + BOOL bEnable +); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief ͼģʹ״̬ +/// \param [in] hCamera ľ +/// \param [out] pEnable ָ룬״̬TRUEΪʹܡ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the image noise reduction module's enable state. +/// \param [in] hCamera Camera handle. +/// \param [out] pEnable Returns status. TRUE, to enable. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetNoiseFilterState( + CameraHandle hCamera, + BOOL* pEnable +); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief λͼɼʱ0ʼ +/// \param [in] hCamera ľ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Resets the time stamp of the image acquisition, starting from 0. +/// \param [in] hCamera Camera handle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraRstTimeStamp( + CameraHandle hCamera +); + +/// @ingroup API_USERDATA +/// \~chinese +/// \brief ûԶݱ浽ķԴ洢С +/// \param [in] hCamera ľ +/// \param [in] uStartAddr ʼַ0ʼ +/// \param [in] pbData ݻָ +/// \param [in] ilen дݵijȣilen + uStartAddrСû󳤶 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ÿͺŵֵ֧û󳤶ȲһԴ豸лȡóϢ +/// \~english +/// \brief Save user-defined data to the camera's non-volatile memory. +/// \param [in] hCamera Camera handle. +/// \param [in] uStartAddr Start address, starting from 0. +/// \param [in] pbData data buffer pointer +/// \param [in] ilen The length of the write data, ilen + uStartAddr must be less than the maximum length of the user area +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note The maximum length of the user data area that each model of camera may support is different. This length information can be obtained from the device's feature description. +MVSDK_API CameraSdkStatus __stdcall CameraSaveUserData( + CameraHandle hCamera, + UINT uStartAddr, + BYTE *pbData, + int ilen +); + +/// @ingroup API_USERDATA +/// \~chinese +/// \brief ķԴ洢жȡûԶݡ +/// \param [in] hCamera ľ +/// \param [in] uStartAddr ʼַ0ʼ +/// \param [out] pbData ݻָ +/// \param [in] ilen ݵijȣilen + uStartAddrСû󳤶 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Read user-defined data from the camera's non-volatile memory. +/// \param [in] hCamera Camera handle. +/// \param [in] uStartAddr Start address, starting from 0. +/// \param [out] pbData data buffer pointer +/// \param [in] ilen The length of the data, ilen + uStartAddr must be less than the maximum length of the user area +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraLoadUserData( + CameraHandle hCamera, + UINT uStartAddr, + BYTE *pbData, + int ilen +); + +/// @ingroup API_USERDATA +/// \~chinese +/// \brief ȡûԶ豸dzơ +/// \param [in] hCamera ľ +/// \param [out] pName ָ룬ָ0βַ豸dzƲ32ֽڣ˸ָָĻڵ32ֽڿռ䡣 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Read user-defined device nicknames. +/// \param [in] hCamera Camera handle. +/// \param [out] pName returns a string that points to the end of 0, the device nickname does not exceed 32 bytes, so the buffer pointed to by this pointer must be greater than or equal to 32 bytes. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetFriendlyName( + CameraHandle hCamera, + char* pName +); + +/// @ingroup API_USERDATA +/// \~chinese +/// \brief ûԶ豸dzơ +/// \param [in] hCamera ľ +/// \param [in] pName ָ룬ָ0βַ豸dzƲ32ֽڣ˸ַָָСڵ32ֽڿռ䡣 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set user-defined device nicknames. +/// \param [in] hCamera Camera handle. +/// \param [in] pName A string that ends with 0, the device nickname does not exceed 32 bytes, so the pointer to the string must be less than or equal to 32 bytes. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetFriendlyName( + CameraHandle hCamera, + char* pName +); + +/// @ingroup API_BASIC +/// \~chinese +/// \brief ȡSDK汾 +/// \param [out] pVersionString ָ룬SDK汾ַָָĻС32ֽ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Read the SDK version number +/// \param [out] pVersionString Returns the SDK version string. The buffer pointed to by this pointer must be larger than 32 bytes +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSdkGetVersionString( + char* pVersionString +); + +/******************************************************/ +// : CameraCheckFwUpdate +// : ̼汾ǷҪ +// : hCamera ľCameraInitá +// pNeedUpdate ָ룬ع̼״̬TRUEʾҪ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +MVSDK_API CameraSdkStatus __stdcall CameraCheckFwUpdate( + CameraHandle hCamera, + BOOL* pNeedUpdate +); + +/// @ingroup API_BASIC +/// \~chinese +/// \brief ù̼汾ַ +/// \param [in] hCamera ľ +/// \param [out] pVersion ָһ32ֽڵĻع̼İ汾ַ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the firmware version string +/// \param [in] hCamera Camera handle. +/// \param [out] pVersion must point to a buffer larger than 32 bytes and return the firmware version string. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetFirmwareVersion( + CameraHandle hCamera, + char* pVersion + ); + +// CameraGetFirmwareVersionͬVersionƴдΪ˼Ա +// Same function as CameraGetFirmwareVersion. Version misspelled, reserved for compatibility +MVSDK_API CameraSdkStatus __stdcall CameraGetFirmwareVision( + CameraHandle hCamera, + char* pVersion +); + +/// @ingroup API_BASIC +/// \~chinese +/// \brief ָ豸öϢ +/// \param [in] hCamera ľ +/// \param [out] pCameraInfo ָ룬豸öϢ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get enumeration information for the specified device +/// \param [in] hCamera Camera handle. +/// \param [out] pCameraInfo Returns the enumeration information for the device. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetEnumInfo( + CameraHandle hCamera, + tSdkCameraDevInfo* pCameraInfo +); + +/// @ingroup API_BASIC +/// \~chinese +/// \brief ָ豸ӿڵİ汾 +/// \param [in] hCamera ľ +/// \param [out] pVersion ָһ32ֽڵĻؽӿڰ汾ַ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the version of the specified device interface +/// \param [in] hCamera Camera handle. +/// \param [out] pVersion points to a buffer larger than 32 bytes and returns the interface version string. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetInerfaceVersion( + CameraHandle hCamera, + char* pVersion +); + +/// @ingroup API_GPIO +/// \~chinese +/// \brief ָIOĵƽ״̬IOΪIOԤɱIOĸ@link #tSdkCameraCapbility.iOutputIoCounts @endlink +/// \param [in] hCamera ľ +/// \param [in] iOutputIOIndex IOţ0ʼ +/// \param [in] uState Ҫ趨״̬1Ϊߣ0Ϊ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the level state of the specified IO. IO is the output IO. The number of programmable output IOs for the camera is determined by @link #tSdkCameraCapbility.iOutputIoCounts @endlink. +/// \param [in] hCamera Camera handle. +/// \param [in] iOutputIOIndex IO index, starting from 0. +/// \param [in] uState The state to set, 1 is high, 0 is low +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetIOState( + CameraHandle hCamera, + INT iOutputIOIndex, + UINT uState +); + +/// @ingroup API_GPIO +/// \~chinese +/// \brief ȡָIOĵƽ״̬IOΪIOԤɱIOĸ@link #tSdkCameraCapbility.iInputIoCounts @endlink +/// \param [in] hCamera ľ +/// \param [in] iInputIOIndex IOţ0ʼ +/// \param [out] puState ָ룬IO״̬,1Ϊߣ0Ϊ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Read the level state of the specified IO, IO is input type IO, the number of programmable output IOs that the camera reserves is decided by @link #tSdkCameraCapbility.iInputIoCounts @endlink. +/// \param [in] hCamera Camera handle. +/// \param [in] iInputIOIndex IO index, starting from 0. +/// \param [out] puState returns IO state, 1 is high, 0 is low +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetIOState( + CameraHandle hCamera, + INT iInputIOIndex, + UINT* puState +); + +/// @ingroup API_GPIO +/// \~chinese +/// \brief IOģʽ +/// \param [in] hCamera ľ +/// \param [in] iInputIOIndex IOţ0ʼ +/// \param [in] iMode IOģʽ,ο@link #emCameraGPIOMode @endlink +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the input IO mode +/// \param [in] hCamera Camera handle. +/// \param [in] iInputIOIndex IO index, starting from 0. +/// \param [in] iMode IO mode, reference @link #emCameraGPIOMode @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetInPutIOMode( + CameraHandle hCamera, + INT iInputIOIndex, + INT iMode + ); + +/// @ingroup API_GPIO +/// \~chinese +/// \brief IOģʽ +/// \param [in] hCamera ľ +/// \param [in] iOutputIOIndex IOţ0ʼ +/// \param [in] iMode IOģʽ,ο@link #emCameraGPIOMode @endlink +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the output IO mode +/// \param [in] hCamera Camera handle. +/// \param [in] iOutputIOIndex IO index, starting from 0. +/// \param [in] iMode IO mode, reference @link #emCameraGPIOMode @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetOutPutIOMode( + CameraHandle hCamera, + INT iOutputIOIndex, + INT iMode + ); + +/// @ingroup API_GPIO +/// \~chinese +/// \brief PWMIJ +/// \param [in] hCamera ľ +/// \param [in] iOutputIOIndex IOţ0ʼ +/// \param [in] iCycle PWMڣλ(us) +/// \param [in] uDuty ռñȣȡֵ1%~99% +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the PWM output parameters +/// \param [in] hCamera Camera handle. +/// \param [in] iOutputIOIndex IO index, starting from 0. +/// \param [in] iCycle Cycle of PWM, unit (us) +/// \param [in] uDuty Occupancy ratio, 1%~99% +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetOutPutPWM( + CameraHandle hCamera, + INT iOutputIOIndex, + UINT iCycle, + UINT uDuty + ); + +// @ingroup API_EXPOSURE +/// \~chinese +/// \brief Զعʱѡ㷨ͬ㷨ڲͬij +/// \param [in] hCamera ľ +/// \param [in] iIspProcessor ѡִи㷨Ķ,ο@link #emSdkIspProcessor @endlink +/// \param [in] iAeAlgorithmSel Ҫѡ㷨š0ʼֵ@link #tSdkCameraCapbility.iAeAlmSwDesc @endlink@link #tSdkCameraCapbility.iAeAlmHdDesc @endlink +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief The algorithm selected when setting up the automatic exposure, different algorithms are suitable for different scenes. +/// \param [in] hCamera Camera handle. +/// \param [in] iIspProcessor Select the object to execute the algorithm, refer to @link #emSdkIspProcessor @endlink +/// \param [in] iAeAlgorithmSel The algorithm number to select. From 0, the maximum value is determined by @link #tSdkCameraCapbility.iAeAlmSwDesc @endlink and @link #tSdkCameraCapbility.iAeAlmHdDesc @endlink. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetAeAlgorithm( + CameraHandle hCamera, + INT iIspProcessor, + INT iAeAlgorithmSel +); + +// @ingroup API_EXPOSURE +/// \~chinese +/// \brief õǰԶعѡ㷨 +/// \param [in] hCamera ľ +/// \param [in] iIspProcessor ѡִи㷨Ķ,ο@link #emSdkIspProcessor @endlink +/// \param [out] piAlgorithmSel صǰѡ㷨š +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the current auto exposure selected algorithm +/// \param [in] hCamera Camera handle. +/// \param [in] iIspProcessor Select the object to execute the algorithm, refer to @link #emSdkIspProcessor @endlink +/// \param [out] piAlgorithmSel Returns the currently selected algorithm number. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetAeAlgorithm( + CameraHandle hCamera, + INT iIspProcessor, + INT* piAlgorithmSel +); + +/// @ingroup API_ISP +/// \~chinese +/// \brief Bayerתɫ㷨 +/// \param [in] hCamera ľ +/// \param [in] iIspProcessor ѡִи㷨Ķ󣬲ο@link #emSdkIspProcessor @endlink +/// \param [in] iAlgorithmSel Ҫѡ㷨š0ʼֵtSdkCameraCapbility.iBayerDecAlmSwDesctSdkCameraCapbility.iBayerDecAlmHdDesc +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set Bayer data to color algorithm. +/// \param [in] hCamera Camera handle. +/// \param [in] iIspProcessor Select the object to execute the algorithm, refer to @link #emSdkIspProcessor @endlink +/// \param [in] iAlgorithmSel The algorithm number to select. From 0, the maximum value is determined by tSdkCameraCapbility.iBayerDecAlmSwDesc and tSdkCameraCapbility.iBayerDecAlmHdDesc. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetBayerDecAlgorithm( + CameraHandle hCamera, + INT iIspProcessor, + INT iAlgorithmSel +); + +/// @ingroup API_ISP +/// \~chinese +/// \brief Bayerתɫѡ㷨 +/// \param [in] hCamera ľ +/// \param [in] iIspProcessor ѡִи㷨Ķ󣬲ο@link #emSdkIspProcessor @endlink +/// \param [in] piAlgorithmSel صǰѡ㷨š +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the algorithm chosen by Bayer data to color. +/// \param [in] hCamera Camera handle. +/// \param [in] iIspProcessor Select the object to execute the algorithm, refer to @link #emSdkIspProcessor @endlink +/// \param [in] piAlgorithmSel Returns the currently selected algorithm number. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetBayerDecAlgorithm( + CameraHandle hCamera, + INT iIspProcessor, + INT* piAlgorithmSel +); + +// @ingroup API_ISP +/// \~chinese +/// \brief ͼԪ㷨ִжPC˻ִ㷨ִʱήPC˵CPUռʡ +/// \param [in] hCamera ľ +/// \param [in] iIspProcessor ο@link #emSdkIspProcessor @endlink +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Sets the algorithm execution object of the image processing unit. The algorithm is executed by the PC or the camera. When executed by the camera, the CPU usage of the PC is reduced. +/// \param [in] hCamera Camera handle. +/// \param [in] iIspProcessor Reference @link #emSdkIspProcessor @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetIspProcessor( + CameraHandle hCamera, + INT iIspProcessor +); + +// @ingroup API_ISP +/// \~chinese +/// \brief ͼԪ㷨ִж +/// \param [in] hCamera ľ +/// \param [out] piIspProcessor ѡĶ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the image processing unit's algorithm execution object. +/// \param [in] hCamera Camera handle. +/// \param [out] piIspProcessor returns the selected object +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetIspProcessor( + CameraHandle hCamera, + INT* piIspProcessor +); + +/// @ingroup API_ISP +/// \~chinese +/// \brief ͼĺڵƽ׼ĬֵΪ0 +/// \param [in] hCamera ľ +/// \param [in] iBlackLevel Ҫ趨ĵƽֵΧΪ0255 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Sets the black level reference of the image. The default value is 0 +/// \param [in] hCamera Camera handle. +/// \param [in] iBlackLevel The value to set. The range is 0 to 255. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetBlackLevel( + CameraHandle hCamera, + INT iBlackLevel +); + +/// @ingroup API_ISP +/// \~chinese +/// \brief ͼĺڵƽ׼ĬֵΪ0 +/// \param [in] hCamera ľ +/// \param [out] piBlackLevel صǰĺڵƽֵΧΪ0255 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the black level of the image, the default value is 0 +/// \param [in] hCamera Camera handle. +/// \param [out] piBlackLevel Returns the current black level value. The range is 0 to 255. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetBlackLevel( + CameraHandle hCamera, + INT* piBlackLevel +); + +/// @ingroup API_ISP +/// \~chinese +/// \brief ͼİ׵ƽ׼ĬֵΪ255 +/// \param [in] hCamera ľ +/// \param [in] iWhiteLevel Ҫ趨ĵƽֵΧΪ0255 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Sets the white level reference of the image. The default value is 255 +/// \param [in] hCamera Camera handle. +/// \param [in] iWhiteLevel The level to be set. The range is 0 to 255. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetWhiteLevel( + CameraHandle hCamera, + INT iWhiteLevel +); + +/// @ingroup API_ISP +/// \~chinese +/// \brief ͼİ׵ƽ׼ĬֵΪ255 +/// \param [in] hCamera ľ +/// \param [out] piWhiteLevel صǰİ׵ƽֵΧΪ0255 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the white level of the image, the default value is 255 +/// \param [in] hCamera Camera handle. +/// \param [out] piWhiteLevel Returns the current white level value. The range is 0 to 255. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetWhiteLevel( + CameraHandle hCamera, + INT* piWhiteLevel +); + +/// @ingroup API_ISP +/// \~chinese +/// \brief @link #CameraImageProcess @endlinkͼʽ +/// \param [in] hCamera ľ +/// \param [in] uFormat ʽ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ֵ֧ĸʽCAMERA_MEDIA_TYPE_MONO8CAMERA_MEDIA_TYPE_MONO16CAMERA_MEDIA_TYPE_RGB8CAMERA_MEDIA_TYPE_RGBA8 CAMERA_MEDIA_TYPE_BGR8CAMERA_MEDIA_TYPE_BGRA8 +/// \~english +/// \brief Sets the output format of image processing for the @link #CameraImageProcess @endlink function. +/// \param [in] hCamera Camera handle. +/// \param [in] uFormat output format. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note Supported formats: CAMERA_MEDIA_TYPE_MONO8, CAMERA_MEDIA_TYPE_MONO16, CAMERA_MEDIA_TYPE_RGB8, CAMERA_MEDIA_TYPE_RGBA8, CAMERA_MEDIA_TYPE_BGR8, CAMERA_MEDIA_TYPE_BGRA8 +MVSDK_API CameraSdkStatus __stdcall CameraSetIspOutFormat( + CameraHandle hCamera, + UINT uFormat +); + +/// @ingroup API_ISP +/// \~chinese +/// \brief ȡʽ +/// \param [in] hCamera ľ +/// \param [out] puFormat صǰʽ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \see CameraSetIspOutFormat +/// \~english +/// \brief Get output format +/// \param [in] hCamera Camera handle. +/// \param [out] puFormat returns the current output format +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \see CameraSetIspOutFormat +MVSDK_API CameraSdkStatus __stdcall CameraGetIspOutFormat( + CameraHandle hCamera, + UINT* puFormat +); + +/// @ingroup API_UTIL +/// \~chinese +/// \brief ôӦַ +/// \param [in] iStatusCode 롣(CameraStatus.h) +/// \return ɹʱشӦַ׵ַ;򷵻NULL +/// \~english +/// \brief Get the description string corresponding to the error code +/// \param [in] iStatusCode error code. (Defined in CameraStatus.h) +/// When the return is successful, the first address of the string corresponding to the error code is returned; otherwise it returns NULL. +MVSDK_API char* __stdcall CameraGetErrorString( + CameraSdkStatus iStatusCode +); + +/// @ingroup API_GRAB +/// \~chinese +/// \brief һ֡ͼݡýӿڻõͼǾRGBʽ +/// \param [in] hCamera ľ +/// \param [out] pImageData ͼݵĻСuOutFormatָĸʽƥ䣬ݻ +/// \param [in] uOutFormat ʽ 0:Mono8 1:rgb24 2:rgba32 3:bgr24 4:bgra32 +/// \param [out] piWidth ָ룬ͼĿ +/// \param [out] piHeight ָ룬ͼĸ߶ +/// \param [in] wTimes ץȡͼijʱʱ䡣 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note Ҫ @link #CameraReleaseImageBuffer @endlink +/// \~english +/// \brief Get a frame of image data. The image obtained by this interface is the processed RGB format. +/// \param [in] hCamera Camera handle. +/// \param [out] pImageData The buffer to receive the image data, the size must match the format specified by uOutFormat, otherwise the data will overflow +/// \param [in] uOutFormat output format 0:Mono8 1:rgb24 2:rgba32 3:bgr24 4:bgra32 +/// \param [out] piWidth Returns the width of the image +/// \param [out] piHeight Returns the height of the image +/// \param [in] wTimes The time-out time for capturing images. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note does not need to call @link #CameraReleaseImageBuffer @endlink +MVSDK_API CameraSdkStatus __stdcall CameraGetImageBufferEx2( + CameraHandle hCamera, + BYTE* pImageData, + UINT uOutFormat, + int* piWidth, + int* piHeight, + UINT wTimes +); + +/// @ingroup API_GRAB +/// \~chinese +/// \brief һ֡ͼݡýӿڻõͼǾRGBʽ +/// \param [in] hCamera ľ +/// \param [out] pImageData ͼݵĻСuOutFormatָĸʽƥ䣬ݻ +/// \param [in] uOutFormat ʽ 0:Mono8 1:rgb24 2:rgba32 3:bgr24 4:bgra32 +/// \param [out] piWidth ָ룬ͼĿ +/// \param [out] piHeight ָ룬ͼĸ߶ +/// \param [out] puTimeStamp ͼʱ +/// \param [in] wTimes ץȡͼijʱʱ䡣 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note Ҫ @link #CameraReleaseImageBuffer @endlink +/// \~english +/// \brief Get a frame of image data. The image obtained by this interface is the processed RGB format. +/// \param [in] hCamera Camera handle. +/// \param [out] pImageData The buffer to receive the image data, the size must match the format specified by uOutFormat, otherwise the data will overflow +/// \param [in] uOutFormat output format 0:Mono8 1:rgb24 2:rgba32 3:bgr24 4:bgra32 +/// \param [out] piWidth Returns the width of the image +/// \param [out] piHeight Returns the height of the image +/// \param [out] puTimeStamp returns image timestamp +/// \param [in] wTimes The time-out time for capturing images. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note does not need to call @link #CameraReleaseImageBuffer @endlink +MVSDK_API CameraSdkStatus __stdcall CameraGetImageBufferEx3( + CameraHandle hCamera, + BYTE*pImageData, + UINT uOutFormat, + int *piWidth, + int *piHeight, + UINT* puTimeStamp, + UINT wTimes +); + +/// @ingroup API_BASIC +/// \~chinese +/// \brief øһЩԡ +/// \param [in] hCamera ľ +/// \param [out] pMaxWidth ظֱʵĿ +/// \param [out] pMaxHeight ظֱʵĸ߶ +/// \param [out] pbColorCamera ظǷDzɫ1ʾɫ0ʾڰ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get some of the camera's features. +/// \param [in] hCamera Camera handle. +/// \param [out] pMaxWidth Returns the width of the camera's maximum resolution +/// \param [out] pMaxHeight Returns the height of the camera's maximum resolution +/// \param [out] pbColorCamera Returns whether the camera is a color camera. 1 indicates a color camera, 0 indicates a black and white camera +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetCapabilityEx2( + CameraHandle hCamera, + int* pMaxWidth, + int* pMaxHeight, + int* pbColorCamera +); + +/// @ingroup API_RECONNECT +/// \~chinese +/// \brief 豸ӻֶָ +/// \param [in] hCamera ľ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \warning ĬʹԶԶģʽñ@see CameraSetAutoConnect +/// \~english +/// \brief Reconnect the device to manually reconnect after the connection is restored +/// \param [in] hCamera Camera handle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \warning The camera automatically enables reconnection by default. Do not call this function in auto reconnect mode. @see CameraSetAutoConnect +MVSDK_API CameraSdkStatus __stdcall CameraReConnect( + CameraHandle hCamera +); + +/// @ingroup API_RECONNECT +/// \~chinese +/// \brief ״̬ڼǷ +/// \param [in] hCamera ľ +/// \return CAMERA_STATUS_SUCCESS(0)ʾѵ +/// \~english +/// \brief Test camera connection status to detect if camera is dropped +/// \param [in] hCamera Camera handle. +/// \return The connection normally returns CAMERA_STATUS_SUCCESS(0). Otherwise it is dropped +MVSDK_API CameraSdkStatus __stdcall CameraConnectTest( + CameraHandle hCamera +); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief LEDʹ״̬LEDͺţ˺ش룬ʾ֧֡ +/// \param [in] hCamera ľ +/// \param [in] index LEDƵţ0ʼֻһɿȵLEDòΪ0 +/// \param [in] enable ʹ״̬ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the camera's LED enable status, without the LED's model, this function returns an error code indicating that it is not supported. +/// \param [in] hCamera Camera handle. +/// \param [in] index The index of the LED, starting from 0. If there is only one LED that can control the brightness, this parameter is 0. +/// \param [in] enable enable state +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetLedEnable( + CameraHandle hCamera, + int index, + BOOL enable + ); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief LEDʹ״̬LEDͺţ˺ش룬ʾ֧֡ +/// \param [in] hCamera ľ +/// \param [in] index LEDƵţ0ʼֻһɿȵLEDòΪ0 +/// \param [out] enable ָ룬LEDʹ״̬ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the camera's LED enable status, without the LED's model, this function returns an error code indicating that it is not supported. +/// \param [in] hCamera Camera handle. +/// \param [in] index The index of the LED, starting from 0. If there is only one LED that can control the brightness, this parameter is 0. +/// \param [out] enable Return LED enable status +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetLedEnable( + CameraHandle hCamera, + int index, + BOOL* enable + ); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief LED״̬LEDͺţ˺ش룬ʾ֧֡ +/// \param [in] hCamera ľ +/// \param [in] index LEDƵţ0ʼֻһɿȵLEDòΪ0 +/// \param [in] onoff LED״̬ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the camera's LED switch status, without the LED's model, this function returns an error code indicating that it is not supported. +/// \param [in] hCamera Camera handle. +/// \param [in] index The index of the LED, starting from 0. If there is only one LED that can control the brightness, this parameter is 0. +/// \param [in] onoff LED on/off status +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetLedOnOff( + CameraHandle hCamera, + int index, + BOOL onoff + ); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief LED״̬LEDͺţ˺ش룬ʾ֧֡ +/// \param [in] hCamera ľ +/// \param [in] index LEDƵţ0ʼֻһɿȵLEDòΪ0 +/// \param [out] onoff LED״̬ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the camera's LED switch status, without the LED model, this function returns an error code that does not support. +/// \param [in] hCamera Camera handle. +/// \param [in] index The index of the LED, starting from 0. If there is only one LED that can control the brightness, this parameter is 0. +/// \param [out] onoff Returns LED switch status +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetLedOnOff( + CameraHandle hCamera, + int index, + BOOL* onoff + ); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief LEDʱ䣬LEDͺţ˺ش룬ʾ֧֡ +/// \param [in] hCamera ľ +/// \param [in] index LEDƵţ0ʼֻһɿȵLEDòΪ0 +/// \param [in] duration LEDʱ䣬λ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the camera's LED duration, without the LED model, this function returns an error code indicating that it is not supported. +/// \param [in] hCamera Camera handle. +/// \param [in] index The index of the LED, starting from 0. If there is only one LED that can control the brightness, this parameter is 0. +/// \param [in] duration LED duration in milliseconds +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetLedDuration( + CameraHandle hCamera, + int index, + UINT duration + ); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief LEDʱ䣬LEDͺţ˺ش룬ʾ֧֡ +/// \param [in] hCamera ľ +/// \param [in] index LEDƵţ0ʼֻһɿȵLEDòΪ0 +/// \param [out] duration LEDʱ䣬λ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the camera's LED duration, without the LED model, this function returns an error code indicating that it is not supported. +/// \param [in] hCamera Camera handle. +/// \param [in] index The index of the LED, starting from 0. If there is only one LED that can control the brightness, this parameter is 0. +/// \param [out] duration Returns the LED duration in milliseconds +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetLedDuration( + CameraHandle hCamera, + int index, + UINT* duration + ); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief LEDȣLEDͺţ˺ش룬ʾ֧֡ +/// \param [in] hCamera ľ +/// \param [in] index LEDƵţ0ʼֻһɿȵLEDòΪ0 +/// \param [in] uBrightness LEDֵΧ0255. 0ʾرգ255 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the camera's LED brightness, without the LED model, this function returns an error code indicating that it is not supported. +/// \param [in] hCamera Camera handle. +/// \param [in] index The index of the LED, starting from 0. If there is only one LED that can control the brightness, this parameter is 0. +/// \param [in] uBrightness LED brightness value, range 0 to 255. 0 means off, 255 brightest. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetLedBrightness( + CameraHandle hCamera, + int index, + UINT uBrightness +); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief LEDȣLEDͺţ˺ش룬ʾ֧֡ +/// \param [in] hCamera ľ +/// \param [in] index LEDƵţ0ʼֻһɿȵLEDòΪ0 +/// \param [out] uBrightness ָ룬LEDֵΧ0255. 0ʾرգ255 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the camera's LED brightness, without the LED model, this function returns an error code that does not support. +/// \param [in] hCamera Camera handle. +/// \param [in] index The index of the LED, starting from 0. If there is only one LED that can control the brightness, this parameter is 0. +/// \param [out] uBrightness Returns the LED brightness value in the range 0 to 255. 0 means off, 255 is the brightest. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetLedBrightness( + CameraHandle hCamera, + int index, + UINT* uBrightness +); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief ʹֹܻ߽Ķ书ܣùܵͺţ˺ش룬ʾ֧֡ +/// \param [in] hCamera ľ +/// \param [in] uEnableMask ʹ״̬룬ӦıλΪ1ʾʹܡ0ΪֹĿǰSDK֧4ɱ༭indexΧΪ03bit0 bit1bit2bit34ʹ״̬ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ùҪ˽ɼзָֻ֣Ķߴ֡ʡ䵽PCϺ󣬻Զƴӳ棬ûбIJ֣úɫ䡣 +/// \~english +/// \brief Enables or disables the camera's multi-zone transfer function. For models without this function, this function returns an error code indicating that it is not supported. +/// \param [in] hCamera Camera handle. +/// \param [in] uEnableMask Area enable mask. The corresponding bit is 1 to enable. 0 is prohibited. Currently, the SDK supports four editable regions. The index range is 0 to 3, that is, bit0, bit1, bit2, and bit3 control the enabling status of the four regions. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note This function is mainly used to split the entire picture collected on the camera side and only transmit specified multiple areas to increase the transmission frame rate. After multiple areas are transferred to the PC, they will be automatically spliced into an entire frame. Parts that have not been transmitted will be filled with black. +MVSDK_API CameraSdkStatus __stdcall CameraEnableTransferRoi( + CameraHandle hCamera, + UINT uEnableMask +); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief IJüˣͼӴϱɼ󣬽ᱻüָͣ˺ش룬ʾ֧֡ +/// \param [in] hCamera ľ +/// \param [in] index ROIţ0ʼ +/// \param [in] X1 ROIϽX +/// \param [in] Y1 ROIϽY +/// \param [in] X2 ROI½X +/// \param [in] Y2 ROI½Y +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Sets the clipping area for camera transmission. On the camera side, after the image is captured from the sensor, it will be cropped to the specified area for transmission. This function returns an error code indicating that it is not supported. +/// \param [in] hCamera Camera handle. +/// \param [in] index The index number of the ROI region, starting at 0. +/// \param [in] X1 The X coordinate of the upper left corner of ROI area +/// \param [in] Y1 The Y coordinate of the upper left corner of ROI area +/// \param [in] X2 The X coordinate of the lower right corner of ROI area +/// \param [in] Y2 The Y coordinate of the lower right corner of ROI area +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetTransferRoi( + CameraHandle hCamera, + int index, + UINT X1, + UINT Y1, + UINT X2, + UINT Y2 +); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief ȡIJüˣͼӴϱɼ󣬽ᱻüָͣ˺ش룬ʾ֧֡ +/// \param [in] hCamera ľ +/// \param [in] index ROIţ0ʼ +/// \param [out] pX1 ROIϽX +/// \param [out] pY1 ROIϽY +/// \param [out] pX2 ROI½X +/// \param [out] pY2 ROI½Y +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the cropped area of the camera transmission. On the camera side, after the image is captured from the sensor, it will be cropped to the specified area for transmission. This function returns an error code indicating that it is not supported. +/// \param [in] hCamera Camera handle. +/// \param [in] index The index number of the ROI region, starting at 0. +/// \param [out] pX1 Returns the X coordinate of the upper left corner of the ROI area +/// \param [out] pY1 Returns the Y coordinate of the upper left corner of the ROI area +/// \param [out] pX2 Returns the X coordinate of the lower right corner of the ROI area +/// \param [out] pY2 Returns the Y coordinate of the lower right corner of the ROI area +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetTransferRoi( + CameraHandle hCamera, + int index, + UINT* pX1, + UINT* pY1, + UINT* pX2, + UINT* pY2 +); + +/// @ingroup API_UTIL +/// \~chinese +/// \brief һζڴռ䡣ܺmallocƣǷصڴalignָֽġ +/// \param [in] size ռĴС +/// \param [in] align ַֽ +/// \return ɹʱط0ֵʾڴ׵ַʧܷNULL +/// \note ڴʹ@link #CameraAlignFree @endlinkͷ +/// \~english +/// \brief Apply for an aligned memory space. The function is similar to malloc, but the returned memory is aligned with the number of bytes specified by align. +/// \param [in] size Size of the space. +/// \param [in] align The number of aligned bytes. +/// \return Successful a non-zero value is returned indicating the first address of the memory. Fails to return NULL. +/// \note Memory allocated must be freed using @link #CameraAlignFree @endlink +MVSDK_API BYTE* __stdcall CameraAlignMalloc( + int size, + int align + ); + +/// @ingroup API_UTIL +/// \~chinese +/// \brief ͷ@link #CameraAlignMalloc @endlinkڴռ䡣 +/// \param [in] membuffer ڴַ +/// \~english +/// \brief Releases the memory space allocated by the @link #CameraAlignMalloc @endlink function. +/// \param [in] membuffer memory address +MVSDK_API void __stdcall CameraAlignFree( + BYTE* membuffer +); + +/// @ingroup API_RECONNECT +/// \~chinese +/// \brief ûԶĬΪá +/// \param [in] hCamera ľ +/// \param [in] bEnable ʹλTRUEʱSDKڲԶǷߣߺԼ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Enables or disables automatic reconnection. The default is enabled. +/// \param [in] hCamera Camera handle. +/// \param [in] bEnable Enables the camera to reconnect. When TRUE, the SDK automatically detects if the camera is dropped and reconnects itself after disconnection. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetAutoConnect(CameraHandle hCamera,BOOL bEnable); + +/// @ingroup API_RECONNECT +/// \~chinese +/// \brief ȡԶʹ״̬ +/// \param [in] hCamera ľ +/// \param [out] pbEnable Զʹ״̬ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get Automatic Reconnect Enable Status +/// \param [in] hCamera Camera handle. +/// \param [out] pbEnable Returns the camera's auto reconnect status +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetAutoConnect(CameraHandle hCamera,BOOL *pbEnable); + +/// @ingroup API_RECONNECT +/// \~chinese +/// \brief ԶĴǰ@link #CameraSetAutoConnect @endlinkʹԶܡĬʹܵġ +/// \param [in] hCamera ľ +/// \param [out] puCounts ԶĴ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the number of times the camera automatically reconnects, provided @link #CameraSetAutoConnect @endlink enables automatic camera reconnection. The default is enabled. +/// \param [in] hCamera Camera handle. +/// \param [out] puCounts returns the number of automatic reconnections +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetReConnectCounts(CameraHandle hCamera,UINT* puCounts); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief ûõ֡ץȡģʽĬΪáܽUSB2.0֧֣ +/// \param [in] hCamera ľ +/// \param [in] bEnable ʹܵ֡ץȡģʽ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ÿɹץȡһ֡SDKͣ״̬ӶռUSBҪڶյij +/// \~english +/// \brief Enables or disables single-frame crawl mode, which is disabled by default. (This function is only supported by USB2.0 camera) +/// \param [in] hCamera Camera handle. +/// \param [in] bEnable enables single-frame mode +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note Whenever a frame is successfully captured, the SDK enters a pause state, so that it no longer occupies the USB bandwidth. It is mainly used in scenes where multiple cameras take pictures. +MVSDK_API CameraSdkStatus __stdcall CameraSetSingleGrabMode(CameraHandle hCamera, BOOL bEnable); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief ĵ֡ץȡʹ״̬ +/// \param [in] hCamera ľ +/// \param [out] pbEnable ĵ֡ץȡģʽʹ״̬ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the camera's single frame capture enable status +/// \param [in] hCamera Camera handle. +/// \param [out] pbEnable Returns the camera's single frame capture mode enable status +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetSingleGrabMode(CameraHandle hCamera, BOOL* pbEnable); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief ڵ֡ץȡģʽʱÿɹץȡһ֡SDKͣ״̬ô˺ʹSDK˳ͣ״̬ʼץȡһ֡ +/// \param [in] hCamera ľ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief When the camera is in the single frame capture mode, the SDK will enter a pause state after successfully capturing a frame. Calling this function will cause the SDK to exit the pause state and start to grab the next frame. +/// \param [in] hCamera Camera handle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraRestartGrab(CameraHandle hCamera); + +/// @ingroup API_UTIL +/// \~chinese +/// \brief ͼƬ +/// \param [in] hCamera ľ +/// \param [in] iAlgorithSel ʹõ㷨,ο@link emEvaluateDefinitionAlgorith @endlinkĶ +/// \param [in] pbyIn ͼݵĻַΪNULL +/// \param [in] pFrInfo ͼ֡ͷϢ +/// \param [out] DefinitionValue صȹֵԽԽ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Image clarity assessment +/// \param [in] hCamera Camera handle. +/// \param [in] iAlgorithSel The currently used evaluation algorithm, see @link emEvaluateDefinitionAlgorith @endlink +/// \param [in] pbyIn The buffer address of the input image data. Cannot be NULL. +/// \param [in] pFrInfo input image frame header information +/// \param [out] DefinitionValue Returns the sharpness value (greater the clearer) +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraEvaluateImageDefinition( + CameraHandle hCamera, + INT iAlgorithSel, + BYTE* pbyIn, + tSdkFrameHead* pFrInfo, + double* DefinitionValue + ); + +/// @ingroup API_UTIL +/// \~chinese +/// \brief ͼл +/// \param [inout] pRgbBuffer ͼݻ +/// \param [in] pFrInfo ͼ֡ͷϢ +/// \param [in] pFontFileName ļ +/// \param [in] FontWidth +/// \param [in] FontHeight ߶ +/// \param [in] pText Ҫ +/// \param [in] Left ֵ +/// \param [in] Top ֵ +/// \param [in] Width ֵ +/// \param [in] Height ֵ +/// \param [in] TextColor ɫRGB +/// \param [in] uFlags ־,@link #emCameraDrawTextFlags @endlinkеĶ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Draw text in the input image data +/// \param [inout] pRgbBuffer image data buffer +/// \param [in] pFrInfo frame header information +/// \param [in] pFontFileName font file name +/// \param [in] FontWidth font width +/// \param [in] FontHeight font height +/// \param [in] pText Text to output +/// \param [in] Left text output rectangle +/// \param [in] Top text output rectangle +/// \param [in] Width Output rectangle of text +/// \param [in] Height the output rectangle of the text +/// \param [in] TextColor Text Color RGB +/// \param [in] uFlags output flags, as defined in @link #emCameraDrawTextFlags @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraDrawText( + BYTE* pRgbBuffer, + tSdkFrameHead* pFrInfo, + char const* pFontFileName, + UINT FontWidth, + UINT FontHeight, + char const* pText, + INT Left, + INT Top, + UINT Width, + UINT Height, + UINT TextColor, + UINT uFlags + ); + +/// @ingroup API_UTIL +/// \~chinese +/// \brief ȡGIGEIPַ +/// \param [in] pCameraInfo 豸Ϣ@link #CameraEnumerateDevice @endlinká +/// \param [out] CamIp IP(ע⣺뱣֤Ļڵ16ֽ) +/// \param [out] CamMask (ע⣺뱣֤Ļڵ16ֽ) +/// \param [out] CamGateWay (ע⣺뱣֤Ļڵ16ֽ) +/// \param [out] EtIp IP(ע⣺뱣֤Ļڵ16ֽ) +/// \param [out] EtMask (ע⣺뱣֤Ļڵ16ֽ) +/// \param [out] EtGateWay (ע⣺뱣֤Ļڵ16ֽ) +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the GIGE camera's IP address +/// \param [in] pCameraInfo camera's device description information can be obtained by @link #CameraEnumerateDevice @endlink function. +/// \param [out] CamIp camera IP (Note: must ensure that the incoming buffer is greater than or equal to 16 bytes) +/// \param [out] CamMask camera subnet mask (Note: must ensure that the incoming buffer is greater than or equal to 16 bytes) +/// \param [out] CamGateWay camera gateway (Note: must ensure that the incoming buffer is greater than or equal to 16 bytes) +/// \param [out] EtIp network card IP (Note: must ensure that the incoming buffer is greater than or equal to 16 bytes) +/// \param [out] EtMask subnet mask (Note: must ensure that the incoming buffer is greater than or equal to 16 bytes) +/// \param [out] EtGateWay NIC Gateway (Note: must ensure that the incoming buffer is greater than or equal to 16 bytes) +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGigeGetIp( + tSdkCameraDevInfo* pCameraInfo, + char* CamIp, + char* CamMask, + char* CamGateWay, + char* EtIp, + char* EtMask, + char* EtGateWay + ); + +/// @ingroup API_UTIL +/// \~chinese +/// \brief GIGEIPַ +/// \param [in] pCameraInfo 豸Ϣ@link #CameraEnumerateDevice @endlinká +/// \param [in] Ip IP(磺192.168.1.100) +/// \param [in] SubMask (磺255.255.255.0) +/// \param [in] GateWay (磺192.168.1.1) +/// \param [in] bPersistent TRUE: Ϊ̶IPFALSEԶIPԲIp, SubMask, GateWay +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the GIGE camera's IP address +/// \param [in] pCameraInfo camera's device description information can be obtained by @link #CameraEnumerateDevice @endlink function. +/// \param [in] Ip camera IP (eg 192.168.1.100) +/// \param [in] SubMask camera subnet mask (eg 255.255.255.0) +/// \param [in] GateWay Camera Gateway (eg 192.168.1.1) +/// \param [in] bPersistent TRUE: Set camera to fixed IP, FALSE: Set camera to assign IP automatically (ignoring parameters Ip, SubMask, GateWay) +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGigeSetIp( + tSdkCameraDevInfo* pCameraInfo, + char const* Ip, + char const* SubMask, + char const* GateWay, + BOOL bPersistent + ); + +/// @ingroup API_UTIL +/// \~chinese +/// \brief ȡGIGEMACַ +/// \param [in] pCameraInfo 豸Ϣ@link #CameraEnumerateDevice @endlinká +/// \param [out] CamMac MAC(ע⣺뱣֤Ļڵ18ֽ) +/// \param [out] EtMac MAC(ע⣺뱣֤Ļڵ18ֽ) +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Select the LUT table in the preset LUT mode. +/// \param [in] pCameraInfo camera's device description information can be obtained by @link #CameraEnumerateDevice @endlink function. +/// \param [out] CamMac camera MAC (Note: must ensure that the incoming buffer is greater than or equal to 18 bytes) +/// \param [out] EtMac network card MAC (Note: must ensure that the incoming buffer is greater than or equal to 18 bytes) +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGigeGetMac( + tSdkCameraDevInfo* pCameraInfo, + char* CamMac, + char* EtMac + ); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief ʹܿӦ +/// \param [in] hCamera ľ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Enable quick response +/// \param [in] hCamera Camera handle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraEnableFastResponse( + CameraHandle hCamera + ); + +/// @ingroup API_DEAD_PIXEL +/// \~chinese +/// \brief ʹܻ +/// \param [in] hCamera ľ +/// \param [in] bEnable TRUE: ʹܻ FALSE: رջ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Enable dead pixel correction +/// \param [in] hCamera Camera handle. +/// \param [in] bEnable TRUE: Enable dead pixel correction FALSE: Turn off dead pixel correction +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetCorrectDeadPixel( + CameraHandle hCamera, + BOOL bEnable + ); + +/// @ingroup API_DEAD_PIXEL +/// \~chinese +/// \brief ȡʹ״̬ +/// \param [in] hCamera ľ +/// \param [out] pbEnable ʹ״̬ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get dead pixel correction enabled +/// \param [in] hCamera Camera handle. +/// \param [out] pbEnable Returns enable state +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetCorrectDeadPixel( + CameraHandle hCamera, + BOOL* pbEnable + ); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief ʹƽУ +/// \param [in] hCamera ľ +/// \param [in] bEnable TRUE: ʹƽУ FALSE: رƽУ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Enable flat field correction +/// \param [in] hCamera Camera handle. +/// \param [in] bEnable TRUE: Enable flat field correction FALSE: Turn off flat field correction +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraFlatFieldingCorrectSetEnable( + CameraHandle hCamera, + BOOL bEnable + ); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief ȡƽУʹ״̬ +/// \param [in] hCamera ľ +/// \param [out] pbEnable ʹ״̬ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get Plane Correction Enable Status +/// \param [in] hCamera Camera handle. +/// \param [out] pbEnable Returns enable state +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraFlatFieldingCorrectGetEnable( + CameraHandle hCamera, + BOOL* pbEnable + ); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief ƽУ +/// \param [in] hCamera ľ +/// \param [in] pDarkFieldingImage ͼƬ +/// \param [in] pDarkFieldingFrInfo ͼƬϢ +/// \param [in] pLightFieldingImage ͼƬ +/// \param [in] pLightFieldingFrInfo ͼƬϢ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set flat field correction parameters +/// \param [in] hCamera Camera handle. +/// \param [in] pDarkFieldingImage dark field image +/// \param [in] pDarkFieldingFrInfo dark field image information +/// \param [in] pLightFieldingImage Brightfield image +/// \param [in] pLightFieldingFrInfo Brightfield image information +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraFlatFieldingCorrectSetParameter( + CameraHandle hCamera, + BYTE const* pDarkFieldingImage, + tSdkFrameHead const* pDarkFieldingFrInfo, + BYTE const* pLightFieldingImage, + tSdkFrameHead const* pLightFieldingFrInfo + ); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief ȡƽУ״̬ +/// \param [in] hCamera ľ +/// \param [out] pbValid زǷЧ +/// \param [out] pFilePath زļ· +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get status of flat field correction parameters +/// \param [in] hCamera Camera handle. +/// \param [out] pbValid Return whether the parameter is valid +/// \param [out] pFilePath Returns the path of the parameter file +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraFlatFieldingCorrectGetParameterState( + CameraHandle hCamera, + BOOL *pbValid, + char *pFilePath + ); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief ƽУļ +/// \param [in] hCamera ľ +/// \param [in] pszFileName ļ· +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Save flat correction parameters to file +/// \param [in] hCamera Camera handle. +/// \param [in] pszFileName file path +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraFlatFieldingCorrectSaveParameterToFile( + CameraHandle hCamera, + char const* pszFileName + ); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief ļмƽУ +/// \param [in] hCamera ľ +/// \param [in] pszFileName ļ· +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Load flat field correction parameters from file +/// \param [in] hCamera Camera handle. +/// \param [in] pszFileName file path +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraFlatFieldingCorrectLoadParameterFromFile( + CameraHandle hCamera, + char const* pszFileName + ); + +/******************************************************/ +// : CameraCommonCall +// : һЩ⹦ܵãοʱһ㲻Ҫá +// : hCamera ľCameraInitá +// pszCall ܼ +// pszResult ýͬpszCallʱ岻ͬ +// uResultBufSize pszResultָĻֽڴС +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +MVSDK_API CameraSdkStatus __stdcall CameraCommonCall( + CameraHandle hCamera, + char const* pszCall, + char* pszResult, + UINT uResultBufSize + ); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief 3D +/// \param [in] hCamera ľ +/// \param [in] bEnable û +/// \param [in] nCount ʹüͼƬн(2-8) +/// \param [in] Weights Ȩأ統ʹ3ͼƬнԴ3(0.3,0.3,0.4)һͼƬȨشǰ2šҪʹȨأ0ʾͼƬȨͬ(0.33,0.33,0.33) +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set 3D noise reduction parameters +/// \param [in] hCamera Camera handle. +/// \param [in] bEnable enable or disable +/// \param [in] nCount Noise reduction using several pictures (2-8) +/// \param [in] Weights Noise reduction weight, such as when using 3 pictures for noise reduction, this parameter can be passed in 3 floating points (0.3, 0.3, 0.4). The weight of the last picture is larger than the first 2 pictures. . If you do not need to use weights, then pass this parameter to 0, indicating that all images have the same weight (0.33, 0.33, 0.33) +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetDenoise3DParams( + CameraHandle hCamera, + BOOL bEnable, + int nCount, + float *Weights + ); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief ȡǰ3D +/// \param [in] hCamera ľ +/// \param [out] bEnable û +/// \param [out] nCount ʹ˼ͼƬн +/// \param [out] bUseWeight Ƿʹ˽Ȩ +/// \param [out] Weights Ȩ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get current 3D noise reduction parameters +/// \param [in] hCamera Camera handle. +/// \param [out] bEnable enable or disable +/// \param [out] nCount uses several pictures for noise reduction +/// \param [out] bUseWeight whether to use noise reduction weights +/// \param [out] Weights Noise Reduction Weights +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetDenoise3DParams( + CameraHandle hCamera, + BOOL *bEnable, + int *nCount, + BOOL *bUseWeight, + float *Weights + ); + +/// @ingroup API_ENHANCE +/// \~chinese +/// \brief һ֡һν봦 +/// \param [in] InFramesHead ֡ͷ +/// \param [in] InFramesData ֡ +/// \param [in] nCount ֡ +/// \param [in] Weights Ȩ +/// \param [out] OutFrameHead ֡ͷ +/// \param [out] OutFrameData ֡ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Perform a noise reduction on a group of frames +/// \param [in] InFramesHead input frame header +/// \param [in] InFramesData input frame data +/// \param [in] nCount Number of input frames +/// \param [in] Weights Noise Reduction Weight +/// \param [out] OutFrameHead output frame header +/// \param [out] OutFrameData output frame data +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraManualDenoise3D( + tSdkFrameHead *InFramesHead, + BYTE **InFramesData, + int nCount, + float *Weights, + tSdkFrameHead *OutFrameHead, + BYTE *OutFrameData + ); + +/// @ingroup API_DEAD_PIXEL +/// \~chinese +/// \brief 򿪻༭ +/// \param [in] hCamera ľ +/// \param [in] hParent øúĴڵľΪNULL +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Open the dead pixels editing panel +/// \param [in] hCamera Camera handle. +/// \param [in] hParent The handle of the window that called the function. Can be NULL. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraCustomizeDeadPixels( + CameraHandle hCamera, + HWND hParent + ); + +/// @ingroup API_DEAD_PIXEL +/// \~chinese +/// \brief ȡ +/// \param [in] hCamera ľ +/// \param [out] pRows y +/// \param [out] pCols x +/// \param [out] pNumPixel ʱʾлĴСʱʾлзصĻ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note pRowspColsΪNULLʱǰĻͨpNumPixel +/// \~english +/// \brief Reading camera dead pixels +/// \param [in] hCamera Camera handle. +/// \param [out] pRows dead pixels y coordinates +/// \param [out] pCols bad x coordinate +/// \param [out] pNumPixel Inputs the size of the row and column buffers. When returned, it indicates the number of bad pixels returned in the row and column buffers. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note When pRows or pCols is NULL, the function will return the camera's current number of dead pixels through pNumPixel. +MVSDK_API CameraSdkStatus __stdcall CameraReadDeadPixels( + CameraHandle hCamera, + USHORT* pRows, + USHORT* pCols, + UINT* pNumPixel + ); + +/// @ingroup API_DEAD_PIXEL +/// \~chinese +/// \brief +/// \param [in] hCamera ľ +/// \param [in] pRows y +/// \param [in] pCols x +/// \param [in] NumPixel леĻ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Add camera dead pixels +/// \param [in] hCamera Camera handle. +/// \param [in] pRows dead point y coordinates +/// \param [in] pCols bad x coordinate +/// \param [in] NumPixel Number of dead pixels in row buffer +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraAddDeadPixels( + CameraHandle hCamera, + USHORT* pRows, + USHORT* pCols, + UINT NumPixel + ); + +/// @ingroup API_DEAD_PIXEL +/// \~chinese +/// \brief ɾָ +/// \param [in] hCamera ľ +/// \param [in] pRows y +/// \param [in] pCols x +/// \param [in] NumPixel леĻ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Delete camera specified dead pixels +/// \param [in] hCamera Camera handle. +/// \param [in] pRows dead point y coordinates +/// \param [in] pCols bad x coordinate +/// \param [in] NumPixel Number of dead pixels in row buffer +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraRemoveDeadPixels( + CameraHandle hCamera, + USHORT* pRows, + USHORT* pCols, + UINT NumPixel + ); + +/// @ingroup API_DEAD_PIXEL +/// \~chinese +/// \brief ɾл +/// \param [in] hCamera ľ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Remove all camera's dead pixels +/// \param [in] hCamera Camera handle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraRemoveAllDeadPixels( + CameraHandle hCamera + ); + +/// @ingroup API_DEAD_PIXEL +/// \~chinese +/// \brief 㵽洢 +/// \param [in] hCamera ľ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Save camera dead pixels to camera memory +/// \param [in] hCamera Camera handle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSaveDeadPixels( + CameraHandle hCamera + ); + +/// @ingroup API_DEAD_PIXEL +/// \~chinese +/// \brief 㵽ļ +/// \param [in] hCamera ľ +/// \param [in] sFileName ļ· +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Save Camera Dead Points to File +/// \param [in] hCamera Camera handle. +/// \param [in] sFileName Full path to the file. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSaveDeadPixelsToFile( + CameraHandle hCamera, + char const* sFileName + ); + +/// @ingroup API_DEAD_PIXEL +/// \~chinese +/// \brief ļ +/// \param [in] hCamera ľ +/// \param [in] sFileName ļ· +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Loading camera dead pixels from file +/// \param [in] hCamera Camera handle. +/// \param [in] sFileName Full path to the file. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraLoadDeadPixelsFromFile( + CameraHandle hCamera, + char const* sFileName + ); + +/// @ingroup API_GRAB +/// \~chinese +/// \brief һ֡ͼݡ +/// \param [in] hCamera ľ +/// \param [out] pFrameInfo ͼ֡ͷϢָ롣 +/// \param [out] pbyBuffer ָͼݵĻָ롣 +/// \param [in] wTimes ץȡͼijʱʱ䡣 +/// \param [in] Priority ȡͼȼ @link #emCameraGetImagePriority @endlink +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ˶һȼ@link #CameraGetImageBuffer @endlinkͬ +/// \~english +/// \brief Get a frame of image data. +/// \param [in] hCamera Camera handle. +/// \param [out] pFrameInfo Frame header information pointer +/// \param [out] pbyBuffer Pointer to the buffer of data for the image. +/// \param [in] wTimes The time-out time for capturing images. +/// \param [in] Priority map priority See: @link #emCameraGetImagePriority @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note Same as @link #CameraGetImageBuffer @endlink except one more priority parameter +MVSDK_API CameraSdkStatus __stdcall CameraGetImageBufferPriority( + CameraHandle hCamera, + tSdkFrameHead* pFrameInfo, + BYTE** pbyBuffer, + UINT wTimes, + UINT Priority + ); + +/// @ingroup API_GRAB +/// \~chinese +/// \brief һ֡ͼݡýӿڻõͼǾRGBʽ +/// \param [in] hCamera ľ +/// \param [out] piWidth ָ룬ͼĿ +/// \param [out] piHeight ָ룬ͼĸ߶ +/// \param [in] wTimes ץȡͼijʱʱ䡣λ롣 +/// \param [in] Priority ȡͼȼ @link #emCameraGetImagePriority @endlink +/// \return ɹʱRGBݻ׵ַ;򷵻0 +/// \note ˶һȼ@link #CameraGetImageBufferEx @endlinkͬ +/// \~english +/// \brief Get a frame of image data. The image obtained by this interface is the processed RGB format. +/// \param [in] hCamera Camera handle. +/// \param [out] piWidth Returns the width of the image +/// \param [out] piHeight Returns the height of the image +/// \param [in] wTimes The time-out time for capturing images. The unit is milliseconds. +/// \param [in] Priority map priority See: @link #emCameraGetImagePriority @endlink +/// \return Returns the first address of the RGB data buffer when successful; otherwise returns 0. +/// \note Same as @link #CameraGetImageBufferEx @endlink except one more priority parameter +MVSDK_API unsigned char* __stdcall CameraGetImageBufferPriorityEx( + CameraHandle hCamera, + INT* piWidth, + INT* piHeight, + UINT wTimes, + UINT Priority + ); + +/// @ingroup API_GRAB +/// \~chinese +/// \brief һ֡ͼݡýӿڻõͼǾRGBʽ +/// \param [in] hCamera ľ +/// \param [out] pImageData ͼݵĻСuOutFormatָĸʽƥ䣬ݻ +/// \param [in] uOutFormat ʽ 0:Mono8 1:rgb24 2:rgba32 3:bgr24 4:bgra32 +/// \param [out] piWidth ָ룬ͼĿ +/// \param [out] piHeight ָ룬ͼĸ߶ +/// \param [in] wTimes ץȡͼijʱʱ䡣λ롣 +/// \param [in] Priority ȡͼȼ @link #emCameraGetImagePriority @endlink +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ˶һȼ@link #CameraGetImageBufferEx2 @endlinkͬ +/// \~english +/// \brief Get a frame of image data. The image obtained by this interface is the processed RGB format. +/// \param [in] hCamera Camera handle. +/// \param [out] pImageData The buffer to receive the image data, the size must match the format specified by uOutFormat, otherwise the data will overflow +/// \param [in] uOutFormat Output Format 0:Mono8 1:rgb24 2:rgba32 3:bgr24 4:bgra32 +/// \param [out] piWidth Returns the width of the image +/// \param [out] piHeight Returns the height of the image +/// \param [in] wTimes The time-out time for capturing images. The unit is milliseconds. +/// \param [in] Priority map priority See: @link #emCameraGetImagePriority @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note Same as @link #CameraGetImageBufferEx2 @endlink except one more priority parameter +MVSDK_API CameraSdkStatus __stdcall CameraGetImageBufferPriorityEx2( + CameraHandle hCamera, + BYTE* pImageData, + UINT uOutFormat, + int* piWidth, + int* piHeight, + UINT wTimes, + UINT Priority + ); + +/// @ingroup API_GRAB +/// \~chinese +/// \brief һ֡ͼݡýӿڻõͼǾRGBʽ +/// \param [in] hCamera ľ +/// \param [out] pImageData ͼݵĻСuOutFormatָĸʽƥ䣬ݻ +/// \param [in] uOutFormat ʽ 0:Mono8 1:rgb24 2:rgba32 3:bgr24 4:bgra32 +/// \param [out] piWidth ָ룬ͼĿ +/// \param [out] piHeight ָ룬ͼĸ߶ +/// \param [out] puTimeStamp ͼʱ +/// \param [in] wTimes ץȡͼijʱʱ䡣 +/// \param [in] Priority ȡͼȼ @link #emCameraGetImagePriority @endlink +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ˶һȼ@link #CameraGetImageBufferEx3 @endlinkͬ +/// \~english +/// \brief Get a frame of image data. The image obtained by this interface is the processed RGB format. +/// \param [in] hCamera Camera handle. +/// \param [out] pImageData The buffer to receive the image data, the size must match the format specified by uOutFormat, otherwise the data will overflow +/// \param [in] uOutFormat output format 0:Mono8 1:rgb24 2:rgba32 3:bgr24 4:bgra32 +/// \param [out] piWidth Returns the width of the image +/// \param [out] piHeight Returns the height of the image +/// \param [out] puTimeStamp returns image timestamp +/// \param [in] wTimes The time-out time for capturing images. +/// \param [in] Priority map priority See: @link #emCameraGetImagePriority @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note Same as @link #CameraGetImageBufferEx3 @endlink except one more priority parameter +MVSDK_API CameraSdkStatus __stdcall CameraGetImageBufferPriorityEx3( + CameraHandle hCamera, + BYTE*pImageData, + UINT uOutFormat, + int *piWidth, + int *piHeight, + UINT* puTimeStamp, + UINT wTimes, + UINT Priority + ); + +/// @ingroup API_GRAB +/// \~chinese +/// \brief ѻ֡ +/// \param [in] hCamera ľ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Clear all cached frames in the camera +/// \param [in] hCamera Camera handle. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraClearBuffer( + CameraHandle hCamera + ); + +/// @ingroup API_TRIGGER +/// \~chinese +/// \brief ִ +/// \param [in] hCamera ľ +/// \param [in] uFlags ܱ־,@link #emCameraSoftTriggerExFlags @endlinkеĶ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \see CameraSoftTrigger +/// \~english +/// \brief Perform a soft trigger. +/// \param [in] hCamera Camera handle. +/// \param [in] uFlags function flags, as defined in @link #emCameraSoftTriggerExFlags @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \see CameraSoftTrigger +MVSDK_API CameraSdkStatus __stdcall CameraSoftTriggerEx( + CameraHandle hCamera, + UINT uFlags + ); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief HDRҪ֧֣HDRܵͺţ˺ش룬ʾ֧֡ +/// \param [in] hCamera ľ +/// \param [in] value HDRϵΧ0.01.0 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Setting the HDR of the camera requires camera support. Models without the HDR function. This function returns an error code indicating that it is not supported. +/// \param [in] hCamera Camera handle. +/// \param [in] value HDR coefficient, range 0.0 to 1.0 +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetHDR( + CameraHandle hCamera, + float value + ); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief ȡHDRҪ֧֣HDRܵͺţ˺ش룬ʾ֧֡ +/// \param [in] hCamera ľ +/// \param [out] value HDRϵΧ0.01.0 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get camera HDR, need camera support, model without HDR function, this function returns an error code, indicating that it is not supported. +/// \param [in] hCamera Camera handle. +/// \param [out] value HDR coefficient, range 0.0 to 1.0 +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetHDR( + CameraHandle hCamera, + float* value + ); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief ȡǰ֡ID֧(ȫϵ֧)˺ش룬ʾ֧֡ +/// \param [in] hCamera ľ +/// \param [out] id ֡ID +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief The ID of the current frame needs to be supported by the camera (supported by the full range of network ports). This function returns an error code indicating that it is not supported. +/// \param [in] hCamera Camera handle. +/// \param [out] id Frame ID +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetFrameID( + CameraHandle hCamera, + UINT* id + ); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief ȡǰ֡ʱ(λ΢) +/// \param [in] hCamera ľ +/// \param [out] TimeStampL ʱ32λ +/// \param [out] TimeStampH ʱ32λ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the timestamp of the current frame (in microseconds) +/// \param [in] hCamera Camera handle. +/// \param [out] TimeStampL timestamp low 32 bits +/// \param [out] TimeStampH Timestamp high 32 bits +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetFrameTimeStamp( + CameraHandle hCamera, + UINT* TimeStampL, + UINT* TimeStampH + ); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief ģʽҪ֧֣ģʽлܵͺţ˺ش룬ʾ֧֡ +/// \param [in] hCamera ľ +/// \param [in] value 0 1 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Setting the camera's gain mode requires camera support. Models without the gain mode switching function. This function returns an error code indicating that it is not supported. +/// \param [in] hCamera Camera handle. +/// \param [in] value 0: low gain 1: high gain +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetHDRGainMode( + CameraHandle hCamera, + int value + ); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief ȡģʽҪ֧֣ģʽлܵͺţ˺ش룬ʾ֧֡ +/// \param [in] hCamera ľ +/// \param [out] value 0 1 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get camera's gain mode, need camera support, model without gain mode switching function, this function returns error code, indicating that it is not supported. +/// \param [in] hCamera Camera handle. +/// \param [out] value 0: low gain 1: high gain +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetHDRGainMode( + CameraHandle hCamera, + int* value + ); + +/// @ingroup API_UTIL +/// \~chinese +/// \brief ֡ݴHBITMAP +/// \param [in] hDC Handle to a device contextWIN32 API CreateDIBitmapIJhdc +/// \param [in] pFrameBuffer ֡ +/// \param [in] pFrameHead ֡ͷ +/// \param [out] outBitmap ´HBITMAPʹҪWIN32 API DeleteObjectͷţ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Create HBITMAP from Frame Data +/// \param [in] hDC Handle to a device context (parameter hdc of WIN32 API CreateDIBitmap) +/// \param [in] pFrameBuffer Frame data +/// \param [in] pFrameHead Frame Header +/// \param [out] outBitmap newly created HBITMAP (need to call WIN32 API DeleteObject after use) +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraCreateDIBitmap( + HDC hDC, + BYTE *pFrameBuffer, + tSdkFrameHead* pFrameHead, + HBITMAP* outBitmap + ); + +/// @ingroup API_UTIL +/// \~chinese +/// \brief ָ֡ +/// \param [in] pFrameBuffer ֡ +/// \param [in] pFrameHead ֡ͷ +/// \param [in] hWnd ĿĴ +/// \param [in] Algorithm 㷨 0ٵԲ 1ٶ +/// \param [in] Mode ģʽ 0: ȱ 1 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Draw frames to the specified window +/// \param [in] pFrameBuffer frame data +/// \param [in] pFrameHead Frame Header +/// \param [in] hWnd destination window +/// \param [in] Algorithm scaling algorithm 0: fast but slightly worse quality 1 slower but better quality +/// \param [in] Mode Zoom Mode 0: Scale 1: Scale Zoom +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraDrawFrameBuffer( + BYTE *pFrameBuffer, + tSdkFrameHead* pFrameHead, + HWND hWnd, + int Algorithm, + int Mode + ); + +/// @ingroup API_UTIL +/// \~chinese +/// \brief ת֡ +/// \param [inout] pFrameBuffer ֡ +/// \param [in] pFrameHead ֡ͷ +/// \param [in] Flags 1: 2 3¡ҽһηת(൱ת180) +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Flip frame data +/// \param [inout] pFrameBuffer frame data +/// \param [in] pFrameHead Frame Header +/// \param [in] Flags 1: Up and down 2: Around 3: Up and down, left and right are all flipped (equivalent to 180 degrees rotation) +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraFlipFrameBuffer( + BYTE *pFrameBuffer, + tSdkFrameHead* pFrameHead, + int Flags + ); + +/// @ingroup API_UTIL +/// \~chinese +/// \brief ת֡ݸʽ +/// \param [in] hCamera ľ +/// \param [in] pInFrameBuffer ֡ +/// \param [out] pOutFrameBuffer ֡ +/// \param [in] outWidth +/// \param [in] outHeight ߶ +/// \param [in] outMediaType ʽ @see CameraSetIspOutFormat +/// \param [inout] pFrameHead ֡ͷϢתɹϢᱻ޸Ϊ֡Ϣ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Conversion frame data format +/// \param [in] hCamera Camera handle. +/// \param [in] pInFrameBuffer input frame data +/// \param [out] pOutFrameBuffer output frame data +/// \param [in] outWidth output width +/// \param [in] outHeight output height +/// \param [in] outMediaType output format @see CameraSetIspOutFormat +/// \param [inout] pFrameHead frame header information (after successful conversion, the information inside will be modified to output frame information) +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraConvertFrameBufferFormat( + CameraHandle hCamera, + BYTE *pInFrameBuffer, + BYTE *pOutFrameBuffer, + int outWidth, + int outHeight, + UINT outMediaType, + tSdkFrameHead* pFrameHead + ); + +/// @ingroup API_RECONNECT +/// \~chinese +/// \brief ״̬ıĻص֪ͨߡʱpCallBackָĻصͻᱻá +/// \param [in] hCamera ľ +/// \param [in] pCallBack صָ롣 +/// \param [in] pContext صĸӲڻصʱøӲᱻ룬ΪNULL +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Sets the callback notification function for camera connection state changes. When the camera is disconnected and reconnected, the callback function pointed to by pCallBack will be called. +/// \param [in] hCamera Camera handle. +/// \param [in] pCallBack callback function pointer. +/// \param [in] pContext Additional parameter of the callback function. This additional parameter will be passed in when the callback function is called. It can be NULL. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetConnectionStatusCallback( + CameraHandle hCamera, + CAMERA_CONNECTION_STATUS_CALLBACK pCallBack, + PVOID pContext + ); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief ùԴģʽϵҪӲ֧֣ +/// \param [in] hCamera ľ +/// \param [in] index +/// \param [in] mode ģʽ0: 1:ֶ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the output mode of the light controller (Smart camera series and hardware support required) +/// \param [in] hCamera Camera handle. +/// \param [in] index controller index +/// \param [in] mode output mode (0: follow strobe 1: manual) +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetLightingControllerMode( + CameraHandle hCamera, + int index, + int mode + ); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief ùԴ״̬ϵҪӲ֧֣ +/// \param [in] hCamera ľ +/// \param [in] index +/// \param [in] state ״̬0:ر 1򿪣 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the output status of the light controller (Smart camera series and hardware support required) +/// \param [in] hCamera Camera handle. +/// \param [in] index controller index +/// \param [in] state output state (0: off 1: on) +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraSetLightingControllerState( + CameraHandle hCamera, + int index, + int state + ); + +/// @ingroup API_MULTI_EYE +/// \~chinese +/// \brief ȡĿĿ +/// \param [in] hCamera ľ +/// \param [out] EyeCount Ŀ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get the number of eyes in the camera +/// \param [in] hCamera Camera handle. +/// \param [out] EyeCount eye count +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGetEyeCount( + CameraHandle hCamera, + int* EyeCount + ); + +/// @ingroup API_MULTI_EYE +/// \~chinese +/// \brief ԶĿ֡ڵijĿͼISP +/// \param [in] hCamera ľ +/// \param [in] iEyeIndex Ŀ +/// \param [in] pbyIn ͼݵĻַΪNULL +/// \param [in] pInFrInfo ͼݵ֡ͷΪNULL +/// \param [out] pbyOut ͼĻַΪNULL +/// \param [out] pOutFrInfo ͼ֡ͷϢΪNULL +/// \param [in] uOutFormat ͼʽ +/// \param [in] uReserved ԤΪ0 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Do ISP for a certain monocular in the multi-camera frame. +/// \param [in] hCamera Camera handle. +/// \param [in] iEyeIndex eye index. +/// \param [in] pbyIn Input the buffer address of the image data, which cannot be NULL. +/// \param [in] pInFrInfo Input the frame header of the image data, which cannot be NULL. +/// \param [out] pbyOut The buffer address of the image output after processing, cannot be NULL. +/// \param [out] pOutFrInfo The header information of the processed image cannot be NULL. +/// \param [in] uOutFormat The output format of the image after processing. +/// \param [in] uReserved Reservation parameters must be set to 0. +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraMultiEyeImageProcess( + CameraHandle hCamera, + int iEyeIndex, + BYTE* pbyIn, + tSdkFrameHead* pInFrInfo, + BYTE* pbyOut, + tSdkFrameHead* pOutFrInfo, + UINT uOutFormat, + UINT uReserved + ); + +#endif diff --git a/others/include/camera/CameraApiLoad.h b/others/include/camera/CameraApiLoad.h new file mode 100644 index 0000000..78a0a49 --- /dev/null +++ b/others/include/camera/CameraApiLoad.h @@ -0,0 +1,5622 @@ +#ifndef _MV_CAM_API +#define _MV_CAM_API + +#include "CameraDefine.h" +#include "CameraStatus.h" + +#ifndef MAX_PATH +#define MAX_PATH 256 +#endif + +//BIG5 TRANS ALLOWED + + +/******************************************************/ +// : CameraSdkInit +// : SDKʼڵκSDKӿǰ +// ȵøýӿڽгʼú +// ڼֻҪһΡ +// : iLanguageSel ѡSDKڲʾϢͽ, +// 0:ʾӢ,1:ʾġ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSdkInit)( + int iLanguageSel + ); + +/******************************************************/ +// : CameraEnumerateDevice +// : ö豸豸бڵCameraInit +// ֮ǰøú豸Ϣ +// : pCameraList 豸бָ롣 +// piNums 豸ĸָ룬ʱpCameraList +// Ԫظʱʵҵ豸 +// ע⣬piNumsֵָʼҲpCameraListԪظ +// пڴ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraEnumerateDevice)( + tSdkCameraDevInfo* pCameraList, + INT* piNums + ); + +/******************************************************/ +// : CameraEnumerateDeviceEx +// : ö豸豸бڵCameraInitEx +// ֮ǰøúö豸 +// : +// ֵ : 豸0ʾޡ +/******************************************************/ +typedef INT (__stdcall *_CameraEnumerateDeviceEx)( + ); + +/******************************************************/ +// : CameraIsOpened +// : 豸ǷѾӦó򿪡ڵCameraInit +// ֮ǰʹøúм⣬Ѿ򿪣 +// CameraInit᷵豸Ѿ򿪵Ĵ롣 +// : pCameraList 豸öϢṹָ룬CameraEnumerateDeviceá +// pOpened 豸״ָ̬룬豸Ƿ񱻴򿪵״̬TRUEΪ򿪣FALSEΪС +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraIsOpened)( + tSdkCameraDevInfo* pCameraList, + BOOL* pOpened + ); + +/******************************************************/ +// : CameraInit +// : ʼʼɹ󣬲ܵκ +// صIJӿڡ +// : pCameraInfo 豸ϢCameraEnumerateDevice +// á +// iParamLoadMode ʼʱʹõIJطʽ-1ʾʹϴ˳ʱIJطʽ +// emTeam ʼʱʹõIJ顣-1ʾϴ˳ʱIJ顣 +// pCameraHandle ľָ룬ʼɹ󣬸ָ +// ظЧڵ +// صIJӿʱҪþҪ +// ڶ֮֡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraInit)( + tSdkCameraDevInfo* pCameraInfo, + int emParamLoadMode, + int emTeam, + CameraHandle* pCameraHandle + ); + +/******************************************************/ +// : CameraInitEx +// : ʼʼɹ󣬲ܵκ +// صIJӿڡ +// : iDeviceIndex ţCameraEnumerateDeviceEx +// iParamLoadMode ʼʱʹõIJطʽ-1ʾʹϴ˳ʱIJطʽ +// Ϊ PARAM_MODE_BY_MODEL ʾͺż +// Ϊ PARAM_MODE_BY_SN ʾкż +// Ϊ PARAM_MODE_BY_NAME ʾdzƼ +// ϸοCameraDefine.h emSdkParameterMode 塣 +// emTeam ʼʱʹõIJ顣-1ʾϴ˳ʱIJ顣 +// pCameraHandle ľָ룬ʼɹ󣬸ָ +// ظЧڵ +// صIJӿʱҪþҪ +// ڶ֮֡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraInitEx)( + int iDeviceIndex, + int iParamLoadMode, + int emTeam, + CameraHandle* pCameraHandle + ); + +/******************************************************/ +// : CameraInitEx2 +// : ʼʼɹ󣬲ܵκ +// صIJӿڡ עҪȵCameraEnumerateDeviceExö +// : CameraName +// pCameraHandle ľָ룬ʼɹ󣬸ָ +// ظЧڵ +// صIJӿʱҪþҪ +// ڶ֮֡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraInitEx2)( + char* CameraName, + CameraHandle *pCameraHandle + ); + +/******************************************************/ +// : CameraSetCallbackFunction +// : ͼ񲶻Ļصµͼ֡ʱ +// pCallBackָĻصͻᱻá +// : hCamera ľCameraInitá +// pCallBack صָ롣 +// pContext صĸӲڻصʱ +// øӲᱻ룬ΪNULL +// ʱЯϢ +// pCallbackOld ڱ浱ǰĻصΪNULL +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetCallbackFunction)( + CameraHandle hCamera, + CAMERA_SNAP_PROC pCallBack, + PVOID pContext, + CAMERA_SNAP_PROC* pCallbackOld + ); + +/******************************************************/ +// : CameraUnInit +// : ʼͷԴ +// : hCamera ľCameraInitá +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraUnInit)( + CameraHandle hCamera + ); + +/******************************************************/ +// : CameraGetInformation +// : Ϣ +// : hCamera ľCameraInitá +// pbuffer ָϢָָ롣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetInformation)( + CameraHandle hCamera, + char** pbuffer + ); + +/******************************************************/ +// : CameraImageProcess +// : õԭʼͼݽдӱͶȡ +// ɫУȴЧõRGB888 +// ʽͼݡ +// : hCamera ľCameraInitá +// pbyIn ͼݵĻַΪNULL +// pbyOut ͼĻַΪNULL +// pFrInfo ͼ֡ͷϢɺ֡ͷϢ +// еͼʽuiMediaType֮ı䡣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraImageProcess)( + CameraHandle hCamera, + BYTE* pbyIn, + BYTE* pbyOut, + tSdkFrameHead* pFrInfo + ); + +/******************************************************/ +// : CameraImageProcessEx +// : õԭʼͼݽдӱͶȡ +// ɫУȴЧõRGB888 +// ʽͼݡ +// : hCamera ľCameraInitá +// pbyIn ͼݵĻַΪNULL +// pbyOut ͼĻַΪNULL +// pFrInfo ͼ֡ͷϢɺ֡ͷϢ +// uOutFormat ͼʽ +// uReserved ԤΪ0 +// еͼʽuiMediaType֮ı䡣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraImageProcessEx)( + CameraHandle hCamera, + BYTE* pbyIn, + BYTE* pbyOut, + tSdkFrameHead* pFrInfo, + UINT uOutFormat, + UINT uReserved + ); + + +/******************************************************/ +// : CameraDisplayInit +// : ʼSDKڲʾģ顣ڵCameraDisplayRGB24 +// ǰȵøúʼڶοУ +// ʹԼķʽͼʾ(CameraDisplayRGB24) +// Ҫñ +// : hCamera ľCameraInitá +// hWndDisplay ʾڵľһΪڵm_hWndԱ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraDisplayInit)( + CameraHandle hCamera, + HWND hWndDisplay + ); + +/******************************************************/ +// : CameraDisplayInitEx +// : ʼSDKڲʾģ顣ڵCameraDisplayRGB24 +// ǰȵøúʼڶοУ +// ʹԼķʽͼʾ(CameraDisplayRGB24) +// Ҫñ ú CameraDisplayInit +// úʱΪͼļһSDKʹڲISPʾӿ +// : pCameraHandle ľ +// hWndDisplay ʾڵľһΪڵm_hWndԱ +// szFileName ͼļ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraDisplayInitEx)( + CameraHandle* pCameraHandle, + HWND hWndDisplay, + char* szFileName + ); + +/******************************************************/ +// : CameraDisplayRGB24 +// : ʾͼ񡣱ùCameraDisplayInit +// ʼܵñ +// : hCamera ľCameraInitá +// pbyRGB24 ͼݻRGB888ʽ +// pFrInfo ͼ֡ͷϢ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraDisplayRGB24)( + CameraHandle hCamera, + BYTE* pbyRGB24, + tSdkFrameHead* pFrInfo + ); + +/******************************************************/ +// : CameraSetDisplayMode +// : ʾģʽùCameraDisplayInit +// гʼܵñ +// : hCamera ľCameraInitá +// iMode ʾģʽDISPLAYMODE_SCALE +// DISPLAYMODE_REAL,μCameraDefine.h +// emSdkDisplayModeĶ塣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetDisplayMode)( + CameraHandle hCamera, + INT iMode + ); + +/******************************************************/ +// : CameraSetDisplayOffset +// : ʾʼƫֵʾģʽΪDISPLAYMODE_REAL +// ʱЧʾؼĴСΪ320X240ͼ +// ijߴΪ640X480ôiOffsetX = 160,iOffsetY = 120ʱ +// ʾͼľ320X240λáù +// CameraDisplayInitгʼܵñ +// : hCamera ľCameraInitá +// iOffsetX ƫƵXꡣ +// iOffsetY ƫƵYꡣ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetDisplayOffset)( + CameraHandle hCamera, + int iOffsetX, + int iOffsetY + ); + +/******************************************************/ +// : CameraSetDisplaySize +// : ʾؼijߴ硣ù +// CameraDisplayInitгʼܵñ +// : hCamera ľCameraInitá +// iWidth +// iHeight ߶ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetDisplaySize)( + CameraHandle hCamera, + INT iWidth, + INT iHeight + ); + +/******************************************************/ +// : CameraGetImageBuffer +// : һ֡ͼݡΪЧʣSDKͼץȡʱ㿽ƣ +// CameraGetImageBufferʵʻںеһַ +// úɹú󣬱CameraReleaseImageBufferͷ +// CameraGetImageBufferõĻ,Աں˼ʹ +// û +// : hCamera ľCameraInitá +// pFrameInfo ͼ֡ͷϢָ롣 +// pbyBuffer ָͼݵĻָ롣 +// 㿽Чʣ +// ʹһָָָ롣 +// UINT wTimes ץȡͼijʱʱ䡣λ롣 +// wTimesʱڻδͼú +// ᷵سʱϢ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetImageBuffer)( + CameraHandle hCamera, + tSdkFrameHead* pFrameInfo, + BYTE** pbyBuffer, + UINT wTimes + ); + +/******************************************************/ +// : CameraGetImageBufferEx +// : һ֡ͼݡýӿڻõͼǾRGBʽúú +// Ҫ CameraReleaseImageBuffer ͷţҲҪfree֮ĺͷ +// ͷŸúصͼݻ +// : hCamera ľCameraInitá +// piWidth ָ룬ͼĿ +// piHeight ָ룬ͼĸ߶ +// UINT wTimes ץȡͼijʱʱ䡣λ롣 +// wTimesʱڻδͼú +// ᷵سʱϢ +// ֵ : ɹʱRGBݻ׵ַ; +// 򷵻0 +/******************************************************/ +typedef unsigned char* (__stdcall *_CameraGetImageBufferEx)( + CameraHandle hCamera, + INT* piWidth, + INT* piHeight, + UINT wTimes + ); + +/******************************************************/ +// : CameraSnapToBuffer +// : ץһͼ񵽻Сץģʽ +// Զлץģʽķֱʽͼ񲶻Ȼ +// 񵽵ݱ浽С +// úɹú󣬱CameraReleaseImageBuffer +// ͷCameraSnapToBufferõĻο +// CameraGetImageBufferĹ֡ +// : hCamera ľCameraInitá +// pFrameInfo ָ룬ͼ֡ͷϢ +// pbyBuffer ָָָ룬ͼ񻺳ĵַ +// uWaitTimeMs ʱʱ䣬λ롣ڸʱڣȻû +// ɹݣ򷵻سʱϢ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSnapToBuffer)( + CameraHandle hCamera, + tSdkFrameHead* pFrameInfo, + BYTE** pbyBuffer, + UINT uWaitTimeMs + ); + +/******************************************************/ +// : CameraReleaseImageBuffer +// : ͷCameraGetImageBufferõĻ +// : hCamera ľCameraInitá +// pbyBuffer CameraGetImageBufferõĻַ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraReleaseImageBuffer)( + CameraHandle hCamera, + BYTE* pbyBuffer + ); + +/******************************************************/ +// : CameraPlay +// : SDK빤ģʽʼ͵ͼ +// ݡǰǴģʽҪյ +// ֡ԺŻͼ +// : hCamera ľCameraInitá +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraPlay)( + CameraHandle hCamera + ); + +/******************************************************/ +// : CameraPause +// : SDKͣģʽͼݣ +// ͬʱҲᷢͣͷŴ +// ͣģʽ£ԶIJãЧ +// : hCamera ľCameraInitá +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraPause)( + CameraHandle hCamera + ); + +/******************************************************/ +// : CameraStop +// : SDKֹͣ״̬һǷʼʱøú +// úãٶIJá +// : hCamera ľCameraInitá +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraStop)( + CameraHandle hCamera + ); + +/******************************************************/ +// : CameraInitRecord +// : ʼһ¼ +// : hCamera ľCameraInitá +// iFormat ¼ĸʽǰֲֻ֧ѹMSCVַʽ +// 0:ѹ1:MSCVʽѹ +// pcSavePath ¼ļ· +// b2GLimit ΪTRUE,ļ2GʱԶָ +// dwQuality ¼ӣԽԽáΧ1100. +// iFrameRate ¼֡ʡ趨ıʵʲɼ֡ʴ +// Ͳ©֡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraInitRecord)( + CameraHandle hCamera, + int iFormat, + char* pcSavePath, + BOOL b2GLimit, + DWORD dwQuality, + int iFrameRate + ); + +/******************************************************/ +// : CameraStopRecord +// : ¼񡣵CameraInitRecord󣬿ͨú +// һ¼񣬲ļ +// : hCamera ľCameraInitá +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraStopRecord)( + CameraHandle hCamera + ); + +/******************************************************/ +// : CameraPushFrame +// : һ֡ݴ¼СCameraInitRecord +// ܵøúCameraStopRecordú󣬲ٵ +// úǵ֡ͷϢЯͼɼʱ +// Ϣ¼Ծ׼ʱͬ֡ʲȶ +// Ӱ졣 +// : hCamera ľCameraInitá +// pbyImageBuffer ͼݻRGBʽ +// pFrInfo ͼ֡ͷϢ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraPushFrame)( + CameraHandle hCamera, + BYTE* pbyImageBuffer, + tSdkFrameHead* pFrInfo + ); + +/******************************************************/ +// : CameraSaveImage +// : ͼ񻺳ݱͼƬļ +// : hCamera ľCameraInitá +// lpszFileName ͼƬļ· +// pbyImageBuffer ͼݻ +// pFrInfo ͼ֡ͷϢ +// byFileType ͼ񱣴ĸʽȡֵΧμCameraDefine.h +// emSdkFileTypeͶ塣Ŀǰ֧ +// BMPJPGPNGRAWָʽRAWʾ +// ԭʼݣRAWʽļҪ +// pbyImageBufferpFrInfoCameraGetImageBuffer +// õݣδCameraImageProcessת +// BMPʽ֮ҪBMPJPG +// PNGʽpbyImageBufferpFrInfo +// CameraImageProcessRGBʽݡ +// ÷ԲοAdvanced̡ +// byQuality ͼ񱣴ӣΪJPGʽ +// ʱòЧΧ1100ʽ +// д0 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSaveImage)( + CameraHandle hCamera, + char* lpszFileName, + BYTE* pbyImageBuffer, + tSdkFrameHead* pFrInfo, + UINT byFileType, + BYTE byQuality + ); + +/******************************************************/ +// : CameraGetImageResolution +// : õǰԤķֱʡ +// : hCamera ľCameraInitá +// psCurVideoSize ṹָ룬ڷصǰķֱʡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetImageResolution)( + CameraHandle hCamera, + tSdkImageResolution* psCurVideoSize + ); + +/******************************************************/ +// : CameraGetImageResolutionEx +// : ȡķֱʡ +// : hCamera ľCameraInitá +// iIndex ţ[0,N]ʾԤķֱ(N ΪԤֱʵһ㲻20),OXFF ʾԶֱ(ROI) +// acDescription ÷ֱʵϢԤֱʱϢЧԶֱʿɺԸϢ +// Mode 0: ͨģʽ 1Sum 2Average 3Skip 4Resample +// ModeSize ͨģʽºԣ1λʾ2X2 ڶλʾ3X3 ... +// x, y ˮƽֱƫ +// width, height +// ZoomWidth,ZoomHeight ʱΪ0ʾ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetImageResolutionEx)( + CameraHandle hCamera, + int* iIndex, + char acDescription[32], + int* Mode, + UINT* ModeSize, + int* x, + int* y, + int* width, + int* height, + int* ZoomWidth, + int* ZoomHeight + ); + +/******************************************************/ +// : CameraSetImageResolution +// : Ԥķֱʡ +// : hCamera ľCameraInitá +// pImageResolution ṹָ룬ڷصǰķֱʡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetImageResolution)( + CameraHandle hCamera, + tSdkImageResolution* pImageResolution + ); + +/******************************************************/ +// : CameraSetImageResolutionEx +// : ķֱʡ +// : hCamera ľCameraInitá +// iIndex ţ[0,N]ʾԤķֱ(N ΪԤֱʵһ㲻20),OXFF ʾԶֱ(ROI) +// Mode 0: ͨģʽ 1Sum 2Average 3Skip 4Resample +// ModeSize ͨģʽºԣ1λʾ2X2 ڶλʾ3X3 ... +// x, y ˮƽֱƫ +// width, height +// ZoomWidth,ZoomHeight ʱΪ0ʾ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetImageResolutionEx)( + CameraHandle hCamera, + int iIndex, + int Mode, + UINT ModeSize, + int x, + int y, + int width, + int height, + int ZoomWidth, + int ZoomHeight + ); + +/******************************************************/ +// : CameraGetMediaType +// : ǰԭʼݵĸʽš +// : hCamera ľCameraInitá +// piMediaType ָ룬ڷصǰʽ͵š +// CameraGetCapabilityԣ +// tSdkCameraCapbilityṹеpMediaTypeDesc +// ԱУʽֵ֧ĸʽ +// piMediaTypeָţǸš +// pMediaTypeDesc[*piMediaType].iMediaTypeʾǰʽ +// 롣ñμCameraDefine.h[ͼʽ]֡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetMediaType)( + CameraHandle hCamera, + INT* piMediaType + ); + +/******************************************************/ +// : CameraSetMediaType +// : ԭʼݸʽ +// : hCamera ľCameraInitá +// iMediaType CameraGetCapabilityԣ +// tSdkCameraCapbilityṹеpMediaTypeDesc +// ԱУʽֵ֧ĸʽ +// iMediaTypeǸš +// pMediaTypeDesc[iMediaType].iMediaTypeʾǰʽ +// 롣ñμCameraDefine.h[ͼʽ]֡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetMediaType)( + CameraHandle hCamera, + INT iMediaType + ); + +/******************************************************/ +// : CameraSetAeState +// : عģʽԶֶ +// : hCamera ľCameraInitá +// bAeState TRUEʹԶع⣻FALSEֹͣԶع⡣ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetAeState)( + CameraHandle hCamera, + BOOL bAeState + ); + +/******************************************************/ +// : CameraGetAeState +// : ǰعģʽ +// : hCamera ľCameraInitá +// pAeState ָ룬ڷԶعʹ״̬ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetAeState)( + CameraHandle hCamera, + BOOL* pAeState + ); + +/******************************************************/ +// : CameraSetSharpness +// : ͼĴ񻯲 +// : hCamera ľCameraInitá +// iSharpness 񻯲ΧCameraGetCapability +// ãһ[0,100]0ʾر񻯴 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetSharpness)( + CameraHandle hCamera, + int iSharpness + ); + +/******************************************************/ +// : CameraGetSharpness +// : ȡǰ趨ֵ +// : hCamera ľCameraInitá +// piSharpness ָ룬صǰ趨񻯵趨ֵ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetSharpness)( + CameraHandle hCamera, + int* piSharpness + ); + +/******************************************************/ +// : CameraSetLutMode +// : IJ任ģʽLUTģʽ +// : hCamera ľCameraInitá +// emLutMode LUTMODE_PARAM_GEN ʾ٤ͶԱȶȲ̬LUT +// LUTMODE_PRESET ʾʹԤLUT +// LUTMODE_USER_DEF ʾʹûԶLUT +// LUTMODE_PARAM_GENĶοCameraDefine.hemSdkLutMode͡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetLutMode)( + CameraHandle hCamera, + int emLutMode + ); + +/******************************************************/ +// : CameraGetLutMode +// : IJ任ģʽLUTģʽ +// : hCamera ľCameraInitá +// pemLutMode ָ룬صǰLUTģʽCameraSetLutMode +// emLutModeͬ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetLutMode)( + CameraHandle hCamera, + int* pemLutMode + ); + +/******************************************************/ +// : CameraSelectLutPreset +// : ѡԤLUTģʽµLUTʹCameraSetLutMode +// LUTģʽΪԤģʽ +// : hCamera ľCameraInitá +// iSel šĸCameraGetCapability +// á +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSelectLutPreset)( + CameraHandle hCamera, + int iSel + ); + +/******************************************************/ +// : CameraGetLutPresetSel +// : ԤLUTģʽµLUTš +// : hCamera ľCameraInitá +// piSel ָ룬رš +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetLutPresetSel)( + CameraHandle hCamera, + int* piSel + ); + +/******************************************************/ +// : CameraSetCustomLut +// : ԶLUTʹCameraSetLutMode +// LUTģʽΪԶģʽ +// : hCamera ľCameraInitá +// iChannel ָҪ趨LUTɫͨΪLUT_CHANNEL_ALLʱ +// ͨLUTͬʱ滻 +// οCameraDefine.hemSdkLutChannel塣 +// pLut ָ룬ָLUTĵַLUTΪ޷Ŷ飬СΪ +// 4096ֱɫͨ04096(12bitɫ)Ӧӳֵ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetCustomLut)( + CameraHandle hCamera, + int iChannel, + USHORT* pLut + ); + +/******************************************************/ +// : CameraGetCustomLut +// : õǰʹõԶLUT +// : hCamera ľCameraInitá +// iChannel ָҪõLUTɫͨΪLUT_CHANNEL_ALLʱ +// غɫͨLUT +// οCameraDefine.hemSdkLutChannel塣 +// pLut ָ룬ָLUTĵַLUTΪ޷Ŷ飬СΪ +// 4096ֱɫͨ04096(12bitɫ)Ӧӳֵ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetCustomLut)( + CameraHandle hCamera, + int iChannel, + USHORT* pLut + ); + +/******************************************************/ +// : CameraGetCurrentLut +// : ǰLUTκLUTģʽ¶Ե, +// ֱ۵Ĺ۲LUTߵı仯 +// : hCamera ľCameraInitá +// iChannel ָҪõLUTɫͨΪLUT_CHANNEL_ALLʱ +// غɫͨLUT +// οCameraDefine.hemSdkLutChannel塣 +// pLut ָ룬ָLUTĵַLUTΪ޷Ŷ飬СΪ +// 4096ֱɫͨ04096(12bitɫ)Ӧӳֵ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetCurrentLut)( + CameraHandle hCamera, + int iChannel, + USHORT* pLut + ); + +/******************************************************/ +// : CameraSetWbMode +// : ƽģʽΪֶԶַʽ +// : hCamera ľCameraInitá +// bAuto TRUEʾʹԶģʽ +// FALSEʾʹֶģʽͨ +// CameraSetOnceWBһΰƽ⡣ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetWbMode)( + CameraHandle hCamera, + BOOL bAuto + ); + +/******************************************************/ +// : CameraGetWbMode +// : õǰİƽģʽ +// : hCamera ľCameraInitá +// pbAuto ָ룬TRUEʾԶģʽFALSE +// Ϊֶģʽ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetWbMode)( + CameraHandle hCamera, + BOOL* pbAuto + ); + +/******************************************************/ +// : CameraSetPresetClrTemp +// : ѡָԤɫģʽ +// : hCamera ľCameraInitá +// iSel Ԥɫµģʽţ0ʼ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetPresetClrTemp)( + CameraHandle hCamera, + int iSel + ); + +/******************************************************/ +// : CameraGetPresetClrTemp +// : õǰѡԤɫģʽ +// : hCamera ľCameraInitá +// piSel ָ룬ѡԤɫ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetPresetClrTemp)( + CameraHandle hCamera, + int* piSel + ); + +/******************************************************/ +// : CameraSetUserClrTempGain +// : Զɫģʽµ +// : hCamera ľCameraInitá +// iRgain ɫ棬Χ0400ʾ04 +// iGgain ɫ棬Χ0400ʾ04 +// iBgain ɫ棬Χ0400ʾ04 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetUserClrTempGain)( + CameraHandle hCamera, + int iRgain, + int iGgain, + int iBgain + ); + + +/******************************************************/ +// : CameraGetUserClrTempGain +// : Զɫģʽµ +// : hCamera ľCameraInitá +// piRgain ָ룬غɫ棬Χ0400ʾ04 +// piGgain ָ룬ɫ棬Χ0400ʾ04 +// piBgain ָ룬ɫ棬Χ0400ʾ04 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetUserClrTempGain)( + CameraHandle hCamera, + int* piRgain, + int* piGgain, + int* piBgain + ); + +/******************************************************/ +// : CameraSetUserClrTempMatrix +// : Զɫģʽµɫ +// : hCamera ľCameraInitá +// pMatrix ָһfloat[3][3]׵ַ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetUserClrTempMatrix)( + CameraHandle hCamera, + float* pMatrix + ); + + +/******************************************************/ +// : CameraGetUserClrTempMatrix +// : Զɫģʽµɫ +// : hCamera ľCameraInitá +// pMatrix ָһfloat[3][3]׵ַ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetUserClrTempMatrix)( + CameraHandle hCamera, + float* pMatrix + ); + +/******************************************************/ +// : CameraSetClrTempMode +// : ðƽʱʹõɫģʽ +// ֵ֧ģʽֱ֣ԶԤԶ塣 +// Զģʽ£Զѡʵɫģʽ +// Ԥģʽ£ʹûָɫģʽ +// Զģʽ£ʹûԶɫ; +// : hCamera ľCameraInitá +// iMode ģʽֻemSdkClrTmpModeжһ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetClrTempMode)( + CameraHandle hCamera, + int iMode + ); + +/******************************************************/ +// : CameraGetClrTempMode +// : ðƽʱʹõɫģʽοCameraSetClrTempMode +// й֡ +// : hCamera ľCameraInitá +// pimode ָ룬ģʽѡ񣬲οemSdkClrTmpModeͶ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetClrTempMode)( + CameraHandle hCamera, + int* pimode + ); + + +/******************************************************/ +// : CameraSetOnceWB +// : ֶƽģʽ£øúһΰƽ⡣ +// ЧʱΪյһ֡ͼʱ +// : hCamera ľCameraInitá +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetOnceWB)( + CameraHandle hCamera + ); + +/******************************************************/ +// : CameraSetOnceBB +// : ִһκƽ +// : hCamera ľCameraInitá +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetOnceBB)( + CameraHandle hCamera + ); + + +/******************************************************/ +// : CameraSetAeTarget +// : 趨ԶعĿֵ趨ΧCameraGetCapability +// á +// : hCamera ľCameraInitá +// iAeTarget Ŀֵ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetAeTarget)( + CameraHandle hCamera, + int iAeTarget + ); + +/******************************************************/ +// : CameraGetAeTarget +// : ԶعĿֵ +// : hCamera ľCameraInitá +// *piAeTarget ָ룬Ŀֵ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetAeTarget)( + CameraHandle hCamera, + int* piAeTarget + ); + +/******************************************************/ +// : CameraSetAeExposureRange +// : 趨ԶعģʽعʱڷΧ +// : hCamera ľCameraInitá +// fMinExposureTime Сعʱ䣨΢룩 +// fMaxExposureTime عʱ䣨΢룩 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetAeExposureRange)( + CameraHandle hCamera, + double fMinExposureTime, + double fMaxExposureTime + ); + +/******************************************************/ +// : CameraGetAeExposureRange +// : ԶعģʽعʱڷΧ +// : hCamera ľCameraInitá +// fMinExposureTime Сعʱ䣨΢룩 +// fMaxExposureTime عʱ䣨΢룩 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetAeExposureRange)( + CameraHandle hCamera, + double* fMinExposureTime, + double* fMaxExposureTime + ); + +/******************************************************/ +// : CameraSetAeAnalogGainRange +// : 趨ԶعģʽڷΧ +// : hCamera ľCameraInitá +// iMinAnalogGain С +// iMaxAnalogGain +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetAeAnalogGainRange)( + CameraHandle hCamera, + int iMinAnalogGain, + int iMaxAnalogGain + ); + +/******************************************************/ +// : CameraGetAeAnalogGainRange +// : ԶعģʽڷΧ +// : hCamera ľCameraInitá +// iMinAnalogGain С +// iMaxAnalogGain +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetAeAnalogGainRange)( + CameraHandle hCamera, + int* iMinAnalogGain, + int* iMaxAnalogGain + ); + +/******************************************************/ +// : CameraSetAeThreshold +// : Զعģʽĵֵ +// : hCamera ľCameraInitá +// iThreshold abs(Ŀ-ͼ) < iThreshold ֹͣԶ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetAeThreshold)( + CameraHandle hCamera, + int iThreshold + ); + +/******************************************************/ +// : CameraGetAeThreshold +// : ȡԶعģʽĵֵ +// : hCamera ľCameraInitá +// iThreshold ȡĵֵ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetAeThreshold)( + CameraHandle hCamera, + int* iThreshold + ); + +/******************************************************/ +// : CameraSetExposureTime +// : عʱ䡣λΪ΢롣CMOSع +// ĵλǰģˣعʱ䲢΢ +// ɵǻᰴȡᡣڵ +// 趨عʱ󣬽ٵCameraGetExposureTime +// ʵ趨ֵ +// : hCamera ľCameraInitá +// fExposureTime عʱ䣬λ΢롣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetExposureTime)( + CameraHandle hCamera, + double fExposureTime + ); + +//******************************************************/ +// : CameraGetExposureLineTime +// : һеعʱ䡣CMOSع +// ĵλǰģˣعʱ䲢΢ +// ɵǻᰴȡᡣ +// þǷCMOSعһжӦʱ䡣 +// : hCamera ľCameraInitá +// double *pfLineTime ָ룬һеعʱ䣬λΪ΢롣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ + +typedef CameraSdkStatus (__stdcall *_CameraGetExposureLineTime)( + CameraHandle hCamera, + double* pfLineTime + ); + +/******************************************************/ +// : CameraGetExposureTime +// : عʱ䡣μCameraSetExposureTime +// Ĺ +// : hCamera ľCameraInitá +// pfExposureTime ָ룬صǰعʱ䣬λ΢롣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetExposureTime)( + CameraHandle hCamera, + double* pfExposureTime + ); + +/******************************************************/ +// : CameraGetExposureTimeRange +// : عʱ䷶Χ +// : hCamera ľCameraInitá +// pfMin ָ룬عʱСֵλ΢롣 +// pfMax ָ룬عʱֵλ΢롣 +// pfStep ָ룬عʱIJֵλ΢롣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetExposureTimeRange)( + CameraHandle hCamera, + double* pfMin, + double* pfMax, + double* pfStep + ); + +/******************************************************/ +// : CameraSetAnalogGain +// : ͼģֵֵCameraGetCapability +// ԽṹsExposeDesc.fAnalogGainStep +// õʵʵͼźŷŴ +// : hCamera ľCameraInitá +// iAnalogGain 趨ģֵ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetAnalogGain)( + CameraHandle hCamera, + INT iAnalogGain + ); + +/******************************************************/ +// : CameraGetAnalogGain +// : ͼźŵģֵμCameraSetAnalogGain +// ϸ˵ +// : hCamera ľCameraInitá +// piAnalogGain ָ룬صǰģֵ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetAnalogGain)( + CameraHandle hCamera, + INT* piAnalogGain + ); + +/******************************************************/ +// : CameraSetGain +// : ͼ档趨ΧCameraGetCapability +// õԽṹsRgbGainRangeԱ +// ʵʵķŴ趨ֵ/100 +// : hCamera ľCameraInitá +// iRGain ɫֵͨ +// iGGain ɫֵͨ +// iBGain ɫֵͨ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetGain)( + CameraHandle hCamera, + int iRGain, + int iGGain, + int iBGain + ); + + +/******************************************************/ +// : CameraGetGain +// : ͼ档μCameraSetGain +// Ĺ֡ +// : hCamera ľCameraInitá +// piRGain ָ룬غɫֵͨ +// piGGain ָ룬ɫֵͨ +// piBGain ָ룬ɫֵͨ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetGain)( + CameraHandle hCamera, + int* piRGain, + int* piGGain, + int* piBGain + ); + + +/******************************************************/ +// : CameraSetGamma +// : 趨LUT̬ģʽµGammaֵ趨ֵ +// ϱSDKڲֻеڶ̬ +// ɵLUTģʽʱŻЧοCameraSetLutMode +// ĺ˵֡ +// : hCamera ľCameraInitá +// iGamma Ҫ趨Gammaֵ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetGamma)( + CameraHandle hCamera, + int iGamma + ); + +/******************************************************/ +// : CameraGetGamma +// : LUT̬ģʽµGammaֵοCameraSetGamma +// Ĺ +// : hCamera ľCameraInitá +// piGamma ָ룬صǰGammaֵ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetGamma)( + CameraHandle hCamera, + int* piGamma + ); + +/******************************************************/ +// : CameraSetContrast +// : 趨LUT̬ģʽµĶԱȶֵ趨ֵ +// ϱSDKڲֻеڶ̬ +// ɵLUTģʽʱŻЧοCameraSetLutMode +// ĺ˵֡ +// : hCamera ľCameraInitá +// iContrast 趨ĶԱȶֵ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetContrast)( + CameraHandle hCamera, + int iContrast + ); + +/******************************************************/ +// : CameraGetContrast +// : LUT̬ģʽµĶԱȶֵο +// CameraSetContrastĹ +// : hCamera ľCameraInitá +// piContrast ָ룬صǰĶԱȶֵ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetContrast)( + CameraHandle hCamera, + int* piContrast + ); + +/******************************************************/ +// : CameraSetSaturation +// : 趨ͼıͶȡԺڰЧ +// 趨ΧCameraGetCapabilityá100ʾ +// ʾԭʼɫȣǿ +// : hCamera ľCameraInitá +// iSaturation 趨ıͶֵ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetSaturation)( + CameraHandle hCamera, + int iSaturation + ); + +/******************************************************/ +// : CameraGetSaturation +// : ͼıͶȡ +// : hCamera ľCameraInitá +// piSaturation ָ룬صǰͼıͶֵ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetSaturation)( + CameraHandle hCamera, + int* piSaturation + ); + +/******************************************************/ +// : CameraSetMonochrome +// : òɫתΪڰ׹ܵʹܡ +// : hCamera ľCameraInitá +// bEnable TRUEʾɫͼתΪڰס +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetMonochrome)( + CameraHandle hCamera, + BOOL bEnable + ); + +/******************************************************/ +// : CameraGetMonochrome +// : òɫתڰ׹ܵʹ״ +// : hCamera ľCameraInitá +// pbEnable ָ롣TRUEʾ˲ɫͼ +// תΪڰͼĹܡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetMonochrome)( + CameraHandle hCamera, + BOOL* pbEnable + ); + +/******************************************************/ +// : CameraSetInverse +// : òͼɫתܵʹܡ +// : hCamera ľCameraInitá +// bEnable TRUEʾͼɫתܣ +// ԻƽƬЧ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetInverse)( + CameraHandle hCamera, + BOOL bEnable + ); + +/******************************************************/ +// : CameraGetInverse +// : ͼɫתܵʹ״̬ +// : hCamera ľCameraInitá +// pbEnable ָ룬ظùʹ״̬ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetInverse)( + CameraHandle hCamera, + BOOL* pbEnable + ); + +/******************************************************/ +// : CameraSetAntiFlick +// : ԶعʱƵܵʹ״ֶ̬ +// عģʽЧ +// : hCamera ľCameraInitá +// bEnable TRUEƵ;FALSEرոùܡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetAntiFlick)( + CameraHandle hCamera, + BOOL bEnable + ); + +/******************************************************/ +// : CameraGetAntiFlick +// : ԶعʱƵܵʹ״̬ +// : hCamera ľCameraInitá +// pbEnable ָ룬ظùܵʹ״̬ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetAntiFlick)( + CameraHandle hCamera, + BOOL* pbEnable + ); + +/******************************************************/ +// : CameraGetLightFrequency +// : ԶعʱƵƵѡ +// : hCamera ľCameraInitá +// piFrequencySel ָ룬ѡš0:50HZ 1:60HZ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetLightFrequency)( + CameraHandle hCamera, + int* piFrequencySel + ); + +/******************************************************/ +// : CameraSetLightFrequency +// : ԶعʱƵƵʡ +// : hCamera ľCameraInitá +// iFrequencySel 0:50HZ , 1:60HZ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetLightFrequency)( + CameraHandle hCamera, + int iFrequencySel + ); + +/******************************************************/ +// : CameraSetFrameSpeed +// : 趨ͼ֡ʡɹѡ֡ģʽ +// CameraGetCapabilityõϢṹiFrameSpeedDesc +// ʾ֡ѡģʽ +// : hCamera ľCameraInitá +// iFrameSpeed ѡ֡ģʽţΧ0 +// CameraGetCapabilityõϢṹiFrameSpeedDesc - 1 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetFrameSpeed)( + CameraHandle hCamera, + int iFrameSpeed + ); + +/******************************************************/ +// : CameraGetFrameSpeed +// : ͼ֡ѡš÷ο +// CameraSetFrameSpeedĹ֡ +// : hCamera ľCameraInitá +// piFrameSpeed ָ룬ѡ֡ģʽš +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetFrameSpeed)( + CameraHandle hCamera, + int* piFrameSpeed + ); + + +/******************************************************/ +// : CameraSetParameterMode +// : 趨ȡĿ +// : hCamera ľCameraInitá +// iMode ȡĶ󡣲οCameraDefine.h +// emSdkParameterModeͶ塣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetParameterMode)( + CameraHandle hCamera, + int iTarget + ); + +/******************************************************/ +// : CameraGetParameterMode +// : +// : hCamera ľCameraInitá +// int* piTarget +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetParameterMode)( + CameraHandle hCamera, + int* piTarget + ); + +/******************************************************/ +// : CameraSetParameterMask +// : òȡ롣غͱʱݸ +// ģǷػ߱档 +// : hCamera ľCameraInitá +// uMask 롣οCameraDefine.hPROP_SHEET_INDEX +// Ͷ塣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetParameterMask)( + CameraHandle hCamera, + UINT uMask + ); + +/******************************************************/ +// : CameraSaveParameter +// : 浱ǰָIJСṩA,B,C,D +// A,B,C,Dռвı档 +// : hCamera ľCameraInitá +// iTeam PARAMETER_TEAM_A 浽A, +// PARAMETER_TEAM_B 浽B, +// PARAMETER_TEAM_C 浽C, +// PARAMETER_TEAM_D 浽D +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSaveParameter)( + CameraHandle hCamera, + int iTeam + ); + +/******************************************************/ +// : CameraReadParameterFromFile +// : PCָIJļмزҹ˾ +// PCΪ.config׺ļλڰװµ +// Camera\ConfigsļС +// : hCamera ľCameraInitá +// *sFileName ļ· +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraReadParameterFromFile)( + CameraHandle hCamera, + char* sFileName + ); + +/******************************************************/ +// : CameraLoadParameter +// : ָIJС +// : hCamera ľCameraInitá +// iTeam PARAMETER_TEAM_A A, +// PARAMETER_TEAM_B B, +// PARAMETER_TEAM_C C, +// PARAMETER_TEAM_D D, +// PARAMETER_TEAM_DEFAULT Ĭϲ +// ͶοCameraDefine.hemSdkParameterTeam +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraLoadParameter)( + CameraHandle hCamera, + int iTeam + ); + +/******************************************************/ +// : CameraGetCurrentParameterGroup +// : õǰѡIJ顣 +// : hCamera ľCameraInitá +// piTeam ָ룬صǰѡIJ顣ֵ +// οCameraLoadParameteriTeam +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetCurrentParameterGroup)( + CameraHandle hCamera, + int* piTeam + ); + +/******************************************************/ +// : CameraSetTransPackLen +// : ͼݵķְС +// ĿǰSDK汾УýӿڽGIGEӿЧ +// 紫ķְС֧־֡ +// ǽѡ8KķְСЧĽʹ +// ռõCPUʱ䡣 +// : hCamera ľCameraInitá +// iPackSel ְѡšְȿ +// ԽṹpPackLenDescԱ +// iPackLenDescԱʾѡķְģʽ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetTransPackLen)( + CameraHandle hCamera, + INT iPackSel + ); + +/******************************************************/ +// : CameraGetTransPackLen +// : ǰְСѡš +// : hCamera ľCameraInitá +// piPackSel ָ룬صǰѡķְСš +// μCameraSetTransPackLeniPackSel +// ˵ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetTransPackLen)( + CameraHandle hCamera, + INT* piPackSel + ); + +/******************************************************/ +// : CameraIsAeWinVisible +// : Զعοڵʾ״̬ +// : hCamera ľCameraInitá +// pbIsVisible ָ룬TRUEʾǰڻ +// ͼϡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraIsAeWinVisible)( + CameraHandle hCamera, + BOOL* pbIsVisible + ); + +/******************************************************/ +// : CameraSetAeWinVisible +// : Զعοڵʾ״̬ô״̬ +// ΪʾCameraImageOverlayܹλ +// Ծεķʽͼϡ +// : hCamera ľCameraInitá +// bIsVisible TRUEΪʾFALSEʾ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetAeWinVisible)( + CameraHandle hCamera, + BOOL bIsVisible + ); + +/******************************************************/ +// : CameraGetAeWindow +// : Զعοڵλá +// : hCamera ľCameraInitá +// piHOff ָ룬شλϽǺֵ +// piVOff ָ룬شλϽֵ +// piWidth ָ룬شڵĿȡ +// piHeight ָ룬شڵĸ߶ȡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetAeWindow)( + CameraHandle hCamera, + INT* piHOff, + INT* piVOff, + INT* piWidth, + INT* piHeight + ); + +/******************************************************/ +// : CameraSetAeWindow +// : ԶعIJοڡ +// : hCamera ľCameraInitá +// iHOff Ͻǵĺ +// iVOff Ͻǵ +// iWidth ڵĿ +// iHeight ڵĸ߶ +// iHOffiVOffiWidthiHeightȫΪ0 +// Ϊÿֱµľ1/2С +// ֱʵı仯仯iHOffiVOffiWidthiHeight +// Ĵλ÷Χ˵ǰֱʷΧڣ +// Զʹþ1/2Сڡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetAeWindow)( + CameraHandle hCamera, + int iHOff, + int iVOff, + int iWidth, + int iHeight + ); + +/******************************************************/ +// : CameraSetMirror +// : ͼΪˮƽʹֱ +// : hCamera ľCameraInitá +// iDir ʾķ0ʾˮƽ1ʾֱ +// bEnable TRUEʹܾ;FALSEֹ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetMirror)( + CameraHandle hCamera, + int iDir, + BOOL bEnable + ); + +/******************************************************/ +// : CameraGetMirror +// : ͼľ״̬ +// : hCamera ľCameraInitá +// iDir ʾҪõľ +// 0ʾˮƽ1ʾֱ +// pbEnable ָ룬TRUEʾiDirָķ +// ʹܡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetMirror)( + CameraHandle hCamera, + int iDir, + BOOL* pbEnable + ); + +/******************************************************/ +// : CameraSetRotate +// : ͼת +// : hCamera ľCameraInitá +// iRot ʾתĽǶȣʱ뷽򣩣0ת 1:90 2:180 3:270ȣ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetRotate)( + CameraHandle hCamera, + int iRot + ); + +/******************************************************/ +// : CameraGetRotate +// : ͼת״̬ +// : hCamera ľCameraInitá +// iRot ʾҪõת +// ʱ뷽򣩣0ת 1:90 2:180 3:270ȣ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetRotate)( + CameraHandle hCamera, + int* iRot + ); + +/******************************************************/ +// : CameraGetWbWindow +// : ðƽοڵλá +// : hCamera ľCameraInitá +// PiHOff ָ룬زοڵϽǺ +// PiVOff ָ룬زοڵϽ +// PiWidth ָ룬زοڵĿȡ +// PiHeight ָ룬زοڵĸ߶ȡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetWbWindow)( + CameraHandle hCamera, + INT* PiHOff, + INT* PiVOff, + INT* PiWidth, + INT* PiHeight + ); + +/******************************************************/ +// : CameraSetWbWindow +// : ðƽοڵλá +// : hCamera ľCameraInitá +// iHOff οڵϽǺꡣ +// iVOff οڵϽꡣ +// iWidth οڵĿȡ +// iHeight οڵĸ߶ȡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetWbWindow)( + CameraHandle hCamera, + INT iHOff, + INT iVOff, + INT iWidth, + INT iHeight + ); + +/******************************************************/ +// : CameraIsWbWinVisible +// : ðƽⴰڵʾ״̬ +// : hCamera ľCameraInitá +// pbShow ָ룬TRUEʾǿɼġ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraIsWbWinVisible)( + CameraHandle hCamera, + BOOL* pbShow + ); + +/******************************************************/ +// : CameraSetWbWinVisible +// : ðƽⴰڵʾ״̬ +// : hCamera ľCameraInitá +// bShow TRUEʾΪɼڵ +// CameraImageOverlayͼϽԾ +// ķʽӰƽοڵλá +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetWbWinVisible)( + CameraHandle hCamera, + BOOL bShow + ); + +/******************************************************/ +// : CameraImageOverlay +// : ͼϵʮߡƽοڡ +// ԶعοڵͼΡֻΪɼ״̬ +// ʮߺͲοڲܱϡ +// ע⣬úͼRGBʽ +// : hCamera ľCameraInitá +// pRgbBuffer ͼݻ +// pFrInfo ͼ֡ͷϢ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraImageOverlay)( + CameraHandle hCamera, + BYTE* pRgbBuffer, + tSdkFrameHead* pFrInfo + ); + +/******************************************************/ +// : CameraSetCrossLine +// : ָʮߵIJ +// : hCamera ľCameraInitá +// iLine ʾҪõڼʮߵ״̬ΧΪ[0,8]9 +// x ʮλõĺֵ +// y ʮλõֵ +// uColor ʮߵɫʽΪ(R|(G<<8)|(B<<16)) +// bVisible ʮߵʾ״̬TRUEʾʾ +// ֻΪʾ״̬ʮߣڵ +// CameraImageOverlayŻᱻӵͼϡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetCrossLine)( + CameraHandle hCamera, + int iLine, + INT x, + INT y, + UINT uColor, + BOOL bVisible + ); + +/******************************************************/ +// : CameraGetCrossLine +// : ָʮߵ״̬ +// : hCamera ľCameraInitá +// iLine ʾҪȡĵڼʮߵ״̬ΧΪ[0,8]9 +// px ָ룬ظʮλõĺꡣ +// py ָ룬ظʮλõĺꡣ +// pcolor ָ룬ظʮߵɫʽΪ(R|(G<<8)|(B<<16)) +// pbVisible ָ룬TRUEʾʮ߿ɼ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetCrossLine)( + CameraHandle hCamera, + INT iLine, + INT* px, + INT* py, + UINT* pcolor, + BOOL* pbVisible + ); + +/******************************************************/ +// : CameraGetCapability +// : ṹ塣ýṹа +// õĸֲķΧϢغIJ +// أҲڶ̬ý档 +// : hCamera ľCameraInitá +// pCameraInfo ָ룬ظĽṹ塣 +// tSdkCameraCapbilityCameraDefine.hж塣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetCapability)( + CameraHandle hCamera, + tSdkCameraCapbility* pCameraInfo + ); + +/******************************************************/ +// : CameraWriteSN +// : кšҹ˾кŷΪ3 +// 0ҹ˾ԶкţʱѾ +// 趨ã12οʹáÿ +// ųȶ32ֽڡ +// : hCamera ľCameraInitá +// pbySN кŵĻ +// iLevel Ҫ趨кżֻ12 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraWriteSN)( + CameraHandle hCamera, + BYTE* pbySN, + INT iLevel + ); + +/******************************************************/ +// : CameraReadSN +// : ȡָкšкŵĶο +// CameraWriteSNĹ֡ +// : hCamera ľCameraInitá +// pbySN кŵĻ +// iLevel Ҫȡкżֻ12 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraReadSN)( + CameraHandle hCamera, + BYTE* pbySN, + INT iLevel + ); +/******************************************************/ +// : CameraSetTriggerDelayTime +// : ӲģʽµĴʱʱ䣬λ΢롣 +// Ӳźٺ󣬾ָʱٿʼɼ +// ͼ񡣽ͺŵָ֧ùܡ鿴 +// Ʒ˵顣 +// : hCamera ľCameraInitá +// uDelayTimeUs Ӳʱλ΢롣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetTriggerDelayTime)( + CameraHandle hCamera, + UINT uDelayTimeUs + ); + +/******************************************************/ +// : CameraGetTriggerDelayTime +// : õǰ趨Ӳʱʱ䡣 +// : hCamera ľCameraInitá +// puDelayTimeUs ָ룬ʱʱ䣬λ΢롣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetTriggerDelayTime)( + CameraHandle hCamera, + UINT* puDelayTimeUs + ); + +/******************************************************/ +// : CameraSetTriggerCount +// : ôģʽµĴ֡Ӳ +// ģʽЧĬΪ1֡һδźŲɼһ֡ͼ +// : hCamera ľCameraInitá +// iCount һδɼ֡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetTriggerCount)( + CameraHandle hCamera, + INT iCount + ); + +/******************************************************/ +// : CameraGetTriggerCount +// : һδ֡ +// : hCamera ľCameraInitá +// INT* piCount +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetTriggerCount)( + CameraHandle hCamera, + INT* piCount + ); + +/******************************************************/ +// : CameraSoftTrigger +// : ִһִк󣬻ᴥCameraSetTriggerCount +// ָ֡ +// : hCamera ľCameraInitá +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSoftTrigger)( + CameraHandle hCamera + ); + +/******************************************************/ +// : CameraSetTriggerMode +// : Ĵģʽ +// : hCamera ľCameraInitá +// iModeSel ģʽѡš趨ģʽ +// CameraGetCapabilityȡο +// CameraDefine.htSdkCameraCapbilityĶ塣 +// һ0ʾɼģʽ1ʾ +// ģʽ2ʾӲģʽ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetTriggerMode)( + CameraHandle hCamera, + int iModeSel + ); + +/******************************************************/ +// : CameraGetTriggerMode +// : Ĵģʽ +// : hCamera ľCameraInitá +// piModeSel ָ룬صǰѡģʽš +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetTriggerMode)( + CameraHandle hCamera, + INT* piModeSel + ); + +/******************************************************/ +// : CameraSetStrobeMode +// : IOŶϵSTROBEźšźſƿƣҲⲿеſơ +// : hCamera ľCameraInitá +// iMode ΪSTROBE_SYNC_WITH_TRIG_AUTO ʹźͬعʱԶSTROBEźš +// ʱЧԿ(CameraSetStrobePolarity) +// ΪSTROBE_SYNC_WITH_TRIG_MANUALʱʹźͬSTROBEʱָʱ(CameraSetStrobeDelayTime) +// ٳָʱ(CameraSetStrobePulseWidth) +// ЧԿ(CameraSetStrobePolarity) +// ΪSTROBE_ALWAYS_HIGHʱSTROBEźźΪ, +// ΪSTROBE_ALWAYS_LOWʱSTROBEźźΪ, +// +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetStrobeMode)( + CameraHandle hCamera, + INT iMode + ); + +/******************************************************/ +// : CameraGetStrobeMode +// : ߵǰSTROBEźõģʽ +// : hCamera ľCameraInitá +// piMode ָ룬STROBE_SYNC_WITH_TRIG_AUTO,STROBE_SYNC_WITH_TRIG_MANUALSTROBE_ALWAYS_HIGHSTROBE_ALWAYS_LOW +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetStrobeMode)( + CameraHandle hCamera, + INT* piMode + ); + +/******************************************************/ +// : CameraSetStrobeDelayTime +// : STROBEźŴSTROBE_SYNC_WITH_TRIGʱͨúԴźʱʱ䡣 +// : hCamera ľCameraInitá +// uDelayTimeUs Դźŵʱʱ䣬λΪusΪ0Ϊ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetStrobeDelayTime)( + CameraHandle hCamera, + UINT uDelayTimeUs + ); + +/******************************************************/ +// : CameraGetStrobeDelayTime +// : STROBEźŴSTROBE_SYNC_WITH_TRIGʱͨúԴźʱʱ䡣 +// : hCamera ľCameraInitá +// upDelayTimeUs ָ룬ʱʱ䣬λus +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetStrobeDelayTime)( + CameraHandle hCamera, + UINT* upDelayTimeUs + ); + +/******************************************************/ +// : CameraSetStrobePulseWidth +// : STROBEźŴSTROBE_SYNC_WITH_TRIGʱͨúȡ +// : hCamera ľCameraInitá +// uTimeUs ĿȣλΪʱus +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetStrobePulseWidth)( + CameraHandle hCamera, + UINT uTimeUs + ); + +/******************************************************/ +// : CameraGetStrobePulseWidth +// : STROBEźŴSTROBE_SYNC_WITH_TRIGʱͨúȡ +// : hCamera ľCameraInitá +// upTimeUs ָ룬ȡλΪʱus +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetStrobePulseWidth)( + CameraHandle hCamera, + UINT* upTimeUs + ); + + +/******************************************************/ +// : CameraSetStrobePolarity +// : STROBEźŴSTROBE_SYNC_WITH_TRIGʱͨúЧƽļԡĬΪЧźŵʱSTROBEźűߡ +// : hCamera ľCameraInitá +// iPolarity STROBEźŵļԣ0Ϊ͵ƽЧ1ΪߵƽЧĬΪߵƽЧ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetStrobePolarity)( + CameraHandle hCamera, + INT iPolarity + ); + +/******************************************************/ +// : CameraGetStrobePolarity +// : ǰSTROBEźŵЧԡĬΪߵƽЧ +// : hCamera ľCameraInitá +// ipPolarity ָ룬STROBEźŵǰЧԡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetStrobePolarity)( + CameraHandle hCamera, + INT* ipPolarity + ); + +/******************************************************/ +// : CameraSetExtTrigSignalType +// : ⴥźŵࡣϱء±ء߸ߡ͵ƽʽ +// : hCamera ľCameraInitá +// iType ⴥźֵ࣬οCameraDefine.h +// emExtTrigSignalͶ塣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetExtTrigSignalType)( + CameraHandle hCamera, + INT iType + ); + +/******************************************************/ +// : CameraGetExtTrigSignalType +// : ǰⴥźŵࡣ +// : hCamera ľCameraInitá +// ipType ָ룬ⴥźֵ࣬οCameraDefine.h +// emExtTrigSignalͶ塣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetExtTrigSignalType)( + CameraHandle hCamera, + INT* ipType + ); + +/******************************************************/ +// : CameraSetExtTrigShutterType +// : ⴥģʽ£ŵķʽĬΪ׼ŷʽ +// ֹŵCMOS֧GRRʽ +// : hCamera ľCameraInitá +// iType ⴥŷʽοCameraDefine.hemExtTrigShutterMode͡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetExtTrigShutterType)( + CameraHandle hCamera, + INT iType + ); + +/******************************************************/ +// : CameraSetExtTrigShutterType +// : ⴥģʽ£ŵķʽĬΪ׼ŷʽ +// ֹŵCMOS֧GRRʽ +// : hCamera ľCameraInitá +// ipType ָ룬صǰ趨ⴥŷʽֵο +// CameraDefine.hemExtTrigShutterMode͡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetExtTrigShutterType)( + CameraHandle hCamera, + INT* ipType + ); + +/******************************************************/ +// : CameraSetExtTrigDelayTime +// : ⴥźʱʱ䣬ĬΪ0λΪ΢롣 +// õֵuDelayTimeUsΪ0ʱյⴥźź󣬽ʱuDelayTimeUs΢ٽͼ񲶻 +// : hCamera ľCameraInitá +// uDelayTimeUs ʱʱ䣬λΪ΢룬ĬΪ0. +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetExtTrigDelayTime)( + CameraHandle hCamera, + UINT uDelayTimeUs + ); + +/******************************************************/ +// : CameraGetExtTrigDelayTime +// : õⴥźʱʱ䣬ĬΪ0λΪ΢롣 +// : hCamera ľCameraInitá +// UINT* upDelayTimeUs +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetExtTrigDelayTime)( + CameraHandle hCamera, + UINT* upDelayTimeUs + ); + +/******************************************************/ +// : CameraSetExtTrigJitterTime +// : ⴥźŵʱ䡣ĬΪ0λΪ΢롣 +// : hCamera ľCameraInitá +// UINT uTimeUs +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetExtTrigJitterTime)( + CameraHandle hCamera, + UINT uTimeUs + ); + +/******************************************************/ +// : CameraGetExtTrigJitterTime +// : õⴥʱ䣬ĬΪ0.λΪ΢ +// : hCamera ľCameraInitá +// UINT* upTimeUs +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetExtTrigJitterTime)( + CameraHandle hCamera, + UINT* upTimeUs + ); + +/******************************************************/ +// : CameraGetExtTrigCapability +// : ⴥ +// : hCamera ľCameraInitá +// puCapabilityMask ָ룬ظⴥ룬οCameraDefine.h +// EXT_TRIG_MASK_ ͷĺ궨塣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetExtTrigCapability)( + CameraHandle hCamera, + UINT* puCapabilityMask + ); + +typedef CameraSdkStatus (__stdcall *_CameraPauseLevelTrigger)( + CameraHandle hCamera + ); + +/******************************************************/ +// : CameraGetResolutionForSnap +// : ץģʽµķֱѡš +// : hCamera ľCameraInitá +// pImageResolution ָ룬ץģʽķֱʡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetResolutionForSnap)( + CameraHandle hCamera, + tSdkImageResolution* pImageResolution + ); + +/******************************************************/ +// : CameraSetResolutionForSnap +// : ץģʽͼķֱʡ +// : hCamera ľCameraInitá +// pImageResolution pImageResolution->iWidth +// pImageResolution->iHeightΪ0 +// ʾ趨Ϊ浱ǰԤֱʡץ +// µͼķֱʻ͵ǰ趨 +// Ԥֱһ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetResolutionForSnap)( + CameraHandle hCamera, + tSdkImageResolution* pImageResolution + ); + +/******************************************************/ +// : CameraCustomizeResolution +// : 򿪷ֱԶ壬ͨӻķʽ +// һԶֱʡ +// : hCamera ľCameraInitá +// pImageCustom ָ룬Զķֱʡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraCustomizeResolution)( + CameraHandle hCamera, + tSdkImageResolution* pImageCustom + ); + +/******************************************************/ +// : CameraCustomizeReferWin +// : 򿪲οԶ塣ͨӻķʽ +// һԶ崰ڵλáһԶƽ +// ԶعIJοڡ +// : hCamera ľCameraInitá +// iWinType ҪɵIJοڵ;0,Զعοڣ +// 1,ƽοڡ +// hParent øúĴڵľΪNULL +// piHOff ָ룬Զ崰ڵϽǺꡣ +// piVOff ָ룬Զ崰ڵϽꡣ +// piWidth ָ룬Զ崰ڵĿȡ +// piHeight ָ룬Զ崰ڵĸ߶ȡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraCustomizeReferWin)( + CameraHandle hCamera, + INT iWinType, + HWND hParent, + INT* piHOff, + INT* piVOff, + INT* piWidth, + INT* piHeight + ); + +/******************************************************/ +// : CameraShowSettingPage +// : ôʾ״̬ȵCameraCreateSettingPage +// ɹôں󣬲ܵñ +// ʾ +// : hCamera ľCameraInitá +// bShow TRUEʾ;FALSEء +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraShowSettingPage)( + CameraHandle hCamera, + BOOL bShow + ); + +/******************************************************/ +// : CameraCreateSettingPage +// : ôڡøúSDKڲ +// ôڣʡȥ¿ +// ýʱ䡣ǿҽʹʹøú +// SDKΪôڡ +// : hCamera ľCameraInitá +// hParent ӦóڵľΪNULL +// pWinText ַָ룬ʾı +// pCallbackFunc ϢĻصӦ¼ʱ +// pCallbackFuncָĺᱻã +// л˲֮IJʱpCallbackFunc +// صʱڲָϢ͡ +// ԷԼĽɵUI +// ֮ͬòΪNULL +// pCallbackCtx صĸӲΪNULLpCallbackCtx +// pCallbackFuncصʱΪ֮һ롣 +// ʹøòһЩжϡ +// uReserved ԤΪ0 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraCreateSettingPage)( + CameraHandle hCamera, + HWND hParent, + char* pWinText, + CAMERA_PAGE_MSG_PROC pCallbackFunc, + PVOID pCallbackCtx, + UINT uReserved + ); + +/******************************************************/ +// : CameraSetActiveSettingSubPage +// : ôڵļҳ档ôж +// ҳ湹ɣú趨ǰһҳ +// Ϊ״̬ʾǰˡ +// : hCamera ľCameraInitá +// index ҳšοCameraDefine.h +// PROP_SHEET_INDEXĶ塣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetActiveSettingSubPage)( + CameraHandle hCamera, + INT index + ); + +typedef CameraSdkStatus (__stdcall *_CameraSetSettingPageParent)( + CameraHandle hCamera, + HWND hParentWnd, + DWORD Flags + ); + +typedef CameraSdkStatus (__stdcall *_CameraGetSettingPageHWnd)( + CameraHandle hCamera, + HWND* hWnd + ); + +/******************************************************/ +// : CameraSpecialControl +// : һЩõĽӿڣοʱһ㲻Ҫ +// á +// : hCamera ľCameraInitá +// dwCtrlCode 롣 +// dwParam 룬ͬdwCtrlCodeʱ岻ͬ +// lpData ӲͬdwCtrlCodeʱ岻ͬ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSpecialControl)( + CameraHandle hCamera, + DWORD dwCtrlCode, + DWORD dwParam, + LPVOID lpData + ); + +/******************************************************/ +// : CameraGetFrameStatistic +// : ֡ʵͳϢ֡Ͷ֡ +// : hCamera ľCameraInitá +// psFrameStatistic ָ룬ͳϢ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetFrameStatistic)( + CameraHandle hCamera, + tSdkFrameStatistic* psFrameStatistic + ); + +/******************************************************/ +// : CameraSetNoiseFilter +// : ͼģʹ״̬ +// : hCamera ľCameraInitá +// bEnable TRUEʹܣFALSEֹ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetNoiseFilter)( + CameraHandle hCamera, + BOOL bEnable + ); + +/******************************************************/ +// : CameraGetNoiseFilterState +// : ͼģʹ״̬ +// : hCamera ľCameraInitá +// *pEnable ָ룬״̬TRUEΪʹܡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetNoiseFilterState)( + CameraHandle hCamera, + BOOL* pEnable + ); + + +/******************************************************/ +// : CameraRstTimeStamp +// : λͼɼʱ0ʼ +// : CameraHandle hCamera +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraRstTimeStamp)( + CameraHandle hCamera + ); + +/******************************************************/ +// : CameraGetCapabilityEx +// : ṹ塣ýṹа +// õĸֲķΧϢغIJ +// أҲڶ̬ý档 +// : sDeviceModel ͺţɨблȡ +// pCameraInfo ָ룬ظĽṹ塣 +// PVOID hCameraHandle +// tSdkCameraCapbilityCameraDefine.hж塣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetCapabilityEx)( + char* sDeviceModel, + tSdkCameraCapbility* pCameraInfo, + PVOID hCameraHandle + ); + +/******************************************************/ +// : CameraFreeCapabilityEx +// : +// أҲڶ̬ý档 +// : sDeviceModel ͺţɨблȡ +// hCameraHandle ָ +// tSdkCameraCapbilityCameraDefine.hж塣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraFreeCapabilityEx)( + char* sDeviceModel, + PVOID hCameraHandle + ); + + + +/******************************************************/ +// : CameraSaveUserData +// : ûԶݱ浽ķԴ洢С +// ÿͺŵֵ֧û󳤶Ȳһ +// Դ豸лȡóϢ +// : hCamera ľCameraInitá +// uStartAddr ʼַ0ʼ +// pbData ݻָ +// ilen дݵijȣilen + uStartAddr +// Сû󳤶 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSaveUserData)( + CameraHandle hCamera, + UINT uStartAddr, + BYTE *pbData, + int ilen + ); + +/******************************************************/ +// : CameraLoadUserData +// : ķԴ洢жȡûԶݡ +// ÿͺŵֵ֧û󳤶Ȳһ +// Դ豸лȡóϢ +// : hCamera ľCameraInitá +// uStartAddr ʼַ0ʼ +// pbData ݻָ룬ضݡ +// ilen ȡݵijȣilen + uStartAddr +// Сû󳤶 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraLoadUserData)( + CameraHandle hCamera, + UINT uStartAddr, + BYTE *pbData, + int ilen + ); + + + +/******************************************************/ +// : CameraGetFriendlyName +// : ȡûԶ豸dzơ +// : hCamera ľCameraInitá +// pName ָ룬ָ0βַ +// 豸dzƲ32ֽڣ˸ָ +// ָĻڵ32ֽڿռ䡣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetFriendlyName)( + CameraHandle hCamera, + char* pName + ); + + +/******************************************************/ +// : CameraSetFriendlyName +// : ûԶ豸dzơ +// : hCamera ľCameraInitá +// pName ָ룬ָ0βַ +// 豸dzƲ32ֽڣ˸ָ +// ַָСڵ32ֽڿռ䡣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetFriendlyName)( + CameraHandle hCamera, + char* pName + ); + + +/******************************************************/ +// : CameraSdkGetVersionString +// : +// : pVersionString ָ룬SDK汾ַ +// ָָĻС +// 32ֽ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSdkGetVersionString)( + char* pVersionString + ); + +/******************************************************/ +// : CameraCheckFwUpdate +// : ̼汾ǷҪ +// : hCamera ľCameraInitá +// pNeedUpdate ָ룬ع̼״̬TRUEʾҪ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraCheckFwUpdate)( + CameraHandle hCamera, + BOOL* pNeedUpdate + ); + +/******************************************************/ +// : CameraGetFirmwareVersion +// : ù̼汾ַ +// : hCamera ľCameraInitá +// pVersion ָһ32ֽڵĻ +// ع̼İ汾ַ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetFirmwareVersion)( + CameraHandle hCamera, + char* pVersion + ); + +/******************************************************/ +// : CameraGetFirmwareVision +// : ù̼汾ַ +// : hCamera ľCameraInitá +// pVersion ָһ32ֽڵĻ +// ع̼İ汾ַ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetFirmwareVision)( + CameraHandle hCamera, + char* pVersion + ); + +/******************************************************/ +// : CameraGetEnumInfo +// : ָ豸öϢ +// : hCamera ľCameraInitá +// pCameraInfo ָ룬豸öϢ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetEnumInfo)( + CameraHandle hCamera, + tSdkCameraDevInfo* pCameraInfo + ); + +/******************************************************/ +// : CameraGetInerfaceVersion +// : ָ豸ӿڵİ汾 +// : hCamera ľCameraInitá +// pVersion ָһ32ֽڵĻؽӿڰ汾ַ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetInerfaceVersion)( + CameraHandle hCamera, + char* pVersion + ); + +/******************************************************/ +// : CameraSetIOState +// : ָIOĵƽ״̬IOΪIO +// ԤɱIOĸtSdkCameraCapbility +// iOutputIoCounts +// : hCamera ľCameraInitá +// iOutputIOIndex IOţ0ʼ +// uState Ҫ趨״̬1Ϊߣ0Ϊ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetIOState)( + CameraHandle hCamera, + INT iOutputIOIndex, + UINT uState + ); + +/******************************************************/ +// : CameraGetIOState +// : ָIOĵƽ״̬IOΪIO +// ԤɱIOĸtSdkCameraCapbility +// iInputIoCounts +// : hCamera ľCameraInitá +// iInputIOIndex IOţ0ʼ +// puState ָ룬IO״̬,1Ϊߣ0Ϊ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetIOState)( + CameraHandle hCamera, + INT iInputIOIndex, + UINT* puState + ); + +/******************************************************/ +// : CameraSetInPutIOMode +// : IOģʽ +// ԤɱIOĸtSdkCameraCapbility +// iInputIoCounts +// : hCamera ľCameraInitá +// iInputIOIndex IOţ0ʼ +// iMode IOģʽ,οCameraDefine.hemCameraGPIOMode +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetInPutIOMode)( + CameraHandle hCamera, + INT iInputIOIndex, + INT iMode + ); + +/******************************************************/ +// : CameraSetOutPutIOMode +// : IOģʽ +// ԤɱIOĸtSdkCameraCapbility +// iOutputIoCounts +// : hCamera ľCameraInitá +// iOutputIOIndex IOţ0ʼ +// iMode IOģʽ,οCameraDefine.hemCameraGPIOMode +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetOutPutIOMode)( + CameraHandle hCamera, + INT iOutputIOIndex, + INT iMode + ); + +/******************************************************/ +// : CameraSetOutPutPWM +// : PWMIJ +// ԤɱIOĸtSdkCameraCapbility +// iOutputIoCounts +// : hCamera ľCameraInitá +// iOutputIOIndex IOţ0ʼ +// iCycle PWMڣλ(us) +// uDuty ռñȣȡֵ1%~99% +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetOutPutPWM)( + CameraHandle hCamera, + INT iOutputIOIndex, + UINT iCycle, + UINT uDuty + ); + +/******************************************************/ +// : CameraSetBayerDecAlgorithm +// : Bayerתɫ㷨 +// : hCamera ľCameraInitá +// iIspProcessor ѡִи㷨Ķ󣬲οCameraDefine.h +// emSdkIspProcessorĶ +// iAlgorithmSel Ҫѡ㷨š0ʼֵtSdkCameraCapbility +// iBayerDecAlmSwDesciBayerDecAlmHdDesc +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetBayerDecAlgorithm)( + CameraHandle hCamera, + INT iIspProcessor, + INT iAlgorithmSel + ); + +/******************************************************/ +// : CameraGetBayerDecAlgorithm +// : Bayerתɫѡ㷨 +// : hCamera ľCameraInitá +// iIspProcessor ѡִи㷨Ķ󣬲οCameraDefine.h +// emSdkIspProcessorĶ +// piAlgorithmSel صǰѡ㷨š0ʼֵtSdkCameraCapbility +// iBayerDecAlmSwDesciBayerDecAlmHdDesc +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetBayerDecAlgorithm)( + CameraHandle hCamera, + INT iIspProcessor, + INT* piAlgorithmSel + ); + +/******************************************************/ +// : CameraSetBlackLevel +// : ͼĺڵƽ׼ĬֵΪ0 +// : hCamera ľCameraInitá +// iBlackLevel Ҫ趨ĵƽֵΧΪ0128 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetBlackLevel) + ( + CameraHandle hCamera, + INT iBlackLevel + ); + +/******************************************************/ +// : CameraGetBlackLevel +// : ͼĺڵƽ׼ĬֵΪ0 +// : hCamera ľCameraInitá +// piBlackLevel صǰĺڵƽֵΧΪ0128 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetBlackLevel) + ( + CameraHandle hCamera, + INT* piBlackLevel + ); + + +/******************************************************/ +// : CameraSetWhiteLevel +// : ͼİ׵ƽ׼ĬֵΪ255 +// : hCamera ľCameraInitá +// iWhiteLevel Ҫ趨ĵƽֵΧΪ128255 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetWhiteLevel) + ( + CameraHandle hCamera, + INT iWhiteLevel + ); + + + +/******************************************************/ +// : CameraGetWhiteLevel +// : ͼİ׵ƽ׼ĬֵΪ255 +// : hCamera ľCameraInitá +// piWhiteLevel صǰİ׵ƽֵΧΪ128255 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetWhiteLevel) + ( + CameraHandle hCamera, + INT* piWhiteLevel + ); + + +/******************************************************/ +// : CameraSetIspOutFormat +// : CameraGetImageBufferͼʽ֧ +// CAMERA_MEDIA_TYPE_MONO8CAMERA_MEDIA_TYPE_RGB8CAMERA_MEDIA_TYPE_RGBA8 +// (CameraDefine.hж)ֱ֣Ӧ8λҶͼ2432λɫͼ +// : hCamera ľCameraInitá +// uFormat Ҫ趨ʽCAMERA_MEDIA_TYPE_MONO8CAMERA_MEDIA_TYPE_RGB8CAMERA_MEDIA_TYPE_RGBA8 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetIspOutFormat) + ( + CameraHandle hCamera, + UINT uFormat + ); + +/******************************************************/ +// : CameraGetIspOutFormat +// : CameraGetImageBufferͼʽ֧ +// CAMERA_MEDIA_TYPE_MONO8CAMERA_MEDIA_TYPE_RGB8CAMERA_MEDIA_TYPE_RGBA8 +// (CameraDefine.hж)ֱ֣Ӧ8λҶͼ2432λɫͼ +// : hCamera ľCameraInitá +// puFormat صǰ趨ĸʽCAMERA_MEDIA_TYPE_MONO8CAMERA_MEDIA_TYPE_RGB8CAMERA_MEDIA_TYPE_RGBA8 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetIspOutFormat) + ( + CameraHandle hCamera, + UINT* puFormat + ); + +/******************************************************/ +// : CameraGetErrorString +// : ôӦַ +// : iStatusCode 롣(CameraStatus.h) +// ֵ : ɹʱشӦַ׵ַ; +// 򷵻NULL +/******************************************************/ +typedef char* (__stdcall *_CameraGetErrorString)( + CameraSdkStatus iStatusCode + ); + +/******************************************************/ +// : CameraGetImageBufferEx2 +// : һ֡ͼݡýӿڻõͼǾRGBʽúú +// Ҫ CameraReleaseImageBuffer ͷţҲҪfree֮ĺͷ +// ͷŸúصͼݻ +// : hCamera ľCameraInitá +// pImageData ͼݵĻСuOutFormatָĸʽƥ䣬ݻ +// piWidth ָ룬ͼĿ +// piHeight ָ룬ͼĸ߶ +// wTimes ץȡͼijʱʱ䡣λ롣 +// wTimesʱڻδͼú +// ᷵سʱϢ +// ֵ : ɹʱRGBݻ׵ַ; +// 򷵻0 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetImageBufferEx2)( + CameraHandle hCamera, + BYTE* pImageData, + UINT uOutFormat, + int* piWidth, + int* piHeight, + UINT wTimes + ); + +/******************************************************/ +// : CameraGetImageBufferEx3 +// : һ֡ͼݡýӿڻõͼǾRGBʽúú +// Ҫ CameraReleaseImageBuffer ͷ. +// uOutFormat 0 : 8 BIT gray 1:rgb24 2:rgba32 3:bgr24 4:bgra32 +// : hCamera ľCameraInitá +// pImageData ͼݵĻСuOutFormatָĸʽƥ䣬ݻ +// piWidth ָ룬ͼĿ +// piHeight ָ룬ͼĸ߶ +// puTimeStamp ޷Σͼʱ +// UINT wTimes ץȡͼijʱʱ䡣λ롣 +// wTimes ʱڻδͼú᷵سʱϢ +// ֵ : ɹʱRGBݻ׵ַ; +// 򷵻0 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetImageBufferEx3)( + CameraHandle hCamera, + BYTE*pImageData, + UINT uOutFormat, + int *piWidth, + int *piHeight, + UINT* puTimeStamp, + UINT wTimes + ); + +/******************************************************/ +// : CameraGetCapabilityEx2 +// : øһЩԡ +// : hCamera ľCameraInitá +// pMaxWidth ظֱʵĿ +// pMaxHeight ظֱʵĸ߶ +// pbColorCamera ظǷDzɫ1ʾɫ0ʾڰ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetCapabilityEx2)( + CameraHandle hCamera, + int* pMaxWidth, + int* pMaxHeight, + int* pbColorCamera + ); + + +/******************************************************/ +// : CameraReConnect +// : 豸USB豸ߺ +// : hCamera ľCameraInitá +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraReConnect)( + CameraHandle hCamera + ); + + +/******************************************************/ +// : CameraConnectTest +// : ״̬ڼǷ +// : hCamera ľCameraInitá +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraConnectTest)( + CameraHandle hCamera + ); + +/******************************************************/ +// : CameraSetLedEnable +// : LEDʹ״̬LEDͺţ˺ش룬ʾ֧֡ +// : hCamera ľCameraInitá +// index LEDƵţ0ʼֻһɿȵLEDòΪ0 +// enable ʹ״̬ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// 򷵻 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetLedEnable)( + CameraHandle hCamera, + int index, + BOOL enable + ); + +/******************************************************/ +// : CameraGetLedEnable +// : LEDʹ״̬LEDͺţ˺ش룬ʾ֧֡ +// : hCamera ľCameraInitá +// index LEDƵţ0ʼֻһɿȵLEDòΪ0 +// enable ָ룬LEDʹ״̬ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// 򷵻 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetLedEnable)( + CameraHandle hCamera, + int index, + BOOL* enable + ); + +/******************************************************/ +// : CameraSetLedOnOff +// : LED״̬LEDͺţ˺ش룬ʾ֧֡ +// : hCamera ľCameraInitá +// index LEDƵţ0ʼֻһɿȵLEDòΪ0 +// onoff LED״̬ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// 򷵻 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetLedOnOff)( + CameraHandle hCamera, + int index, + BOOL onoff + ); + +/******************************************************/ +// : CameraGetLedOnOff +// : LED״̬LEDͺţ˺ش룬ʾ֧֡ +// : hCamera ľCameraInitá +// index LEDƵţ0ʼֻһɿȵLEDòΪ0 +// onoff ָ룬LED״̬ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// 򷵻 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetLedOnOff)( + CameraHandle hCamera, + int index, + BOOL* onoff + ); + +/******************************************************/ +// : CameraSetLedDuration +// : LEDʱ䣬LEDͺţ˺ش룬ʾ֧֡ +// : hCamera ľCameraInitá +// index LEDƵţ0ʼֻһɿȵLEDòΪ0 +// duration LEDʱ䣬λ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// 򷵻 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetLedDuration)( + CameraHandle hCamera, + int index, + UINT duration + ); + +/******************************************************/ +// : CameraGetLedDuration +// : LEDʱ䣬LEDͺţ˺ش룬ʾ֧֡ +// : hCamera ľCameraInitá +// index LEDƵţ0ʼֻһɿȵLEDòΪ0 +// duration ָ룬LEDʱ䣬λ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// 򷵻 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetLedDuration)( + CameraHandle hCamera, + int index, + UINT* duration + ); + +/******************************************************/ +// : CameraSetLedLightless +// : LEDȣLEDͺţ˺ش룬ʾ֧֡ +// : hCamera ľCameraInitá +// index LEDƵţ0ʼֻһɿȵLEDòΪ0 +// uLightless LEDֵΧ0255. 0ʾرգ255 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// 򷵻 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetLedBrightness)( + CameraHandle hCamera, + int index, + UINT uLightless + ); + +/******************************************************/ +// : CameraGetLedLightless +// : LEDȣLEDͺţ˺ش룬ʾ֧֡ +// : hCamera ľCameraInitá +// index LEDƵţ0ʼֻһɿȵLEDòΪ0 +// uLightless ָ룬LEDֵΧ0255. 0ʾرգ255 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// 򷵻 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetLedBrightness)( + CameraHandle hCamera, + int index, + UINT* uLightless + ); + + +/******************************************************/ +// : CameraEnableTransferRoi +// : ʹֹܻ߽Ķ书ܣùܵͺţ˺ش룬ʾ֧֡ +// ùҪ˽ɼзָֻ֣Ķߴ֡ʡ +// 䵽PCϺ󣬻Զƴӳ棬ûбIJ֣úɫ䡣 +// : hCamera ľCameraInitá +// index ROIţ0ʼ +// uEnableMask ʹ״̬룬ӦıλΪ1ʾʹܡ0ΪֹĿǰSDK֧4ɱ༭indexΧΪ03bit0 bit1bit2bit34ʹ״̬ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// ڲֶ֧ROIͺţú᷵ CAMERA_STATUS_NOT_SUPPORTED(-4) ʾ֧ +// 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraEnableTransferRoi)( + CameraHandle hCamera, + UINT uEnableMask + ); + + +/******************************************************/ +// : CameraSetTransferRoi +// : IJüˣͼӴϱɼ󣬽ᱻüָͣ˺ش룬ʾ֧֡ +// : hCamera ľCameraInitá +// index ROIţ0ʼ +// X1,Y1 ROIϽ +// X2,Y2 ROIϽ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// ڲֶ֧ROIͺţú᷵ CAMERA_STATUS_NOT_SUPPORTED(-4) ʾ֧ +// 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetTransferRoi)( + CameraHandle hCamera, + int index, + UINT X1, + UINT Y1, + UINT X2, + UINT Y2 + ); + + +/******************************************************/ +// : CameraGetTransferRoi +// : IJüˣͼӴϱɼ󣬽ᱻüָͣ˺ش룬ʾ֧֡ +// : hCamera ľCameraInitá +// index ROIţ0ʼ +// pX1,pY1 ROIϽ +// pX2,pY2 ROIϽ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// ڲֶ֧ROIͺţú᷵ CAMERA_STATUS_NOT_SUPPORTED(-4) ʾ֧ +// 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetTransferRoi)( + CameraHandle hCamera, + int index, + UINT* pX1, + UINT* pY1, + UINT* pX2, + UINT* pY2 + ); + +/******************************************************/ +// : CameraAlignMalloc +// : һζڴռ䡣ܺmallocƣ +// Ƿصڴalignָֽġ +// : size ռĴС +// align ַֽ +// ֵ : ɹʱط0ֵʾڴ׵ַʧܷNULL +/******************************************************/ + +typedef BYTE* (__stdcall *_CameraAlignMalloc)( + int size, + int align + ); + +/******************************************************/ +// : CameraAlignFree +// : ͷCameraAlignMallocڴռ䡣 +// : membuffer CameraAlignMallocصڴ׵ַ +// ֵ : ޡ +/******************************************************/ +typedef void (__stdcall *_CameraAlignFree)( + BYTE* membuffer + ); + + +/******************************************************/ +// : CameraSetAutoConnect +// : Զʹ +// : hCamera ľCameraInitá +// bEnable ʹλTRUEʱSDKڲԶǷߣߺԼ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// ڲֵ֧ͺţú᷵ CAMERA_STATUS_NOT_SUPPORTED(-4) ʾ֧ +// 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetAutoConnect)( + CameraHandle hCamera, + BOOL bEnable + ); + +/******************************************************/ +// : CameraGetAutoConnect +// : ȡԶʹ +// : hCamera ľCameraInitá +// pbEnable ʹ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// ڲֵ֧ͺţú᷵ CAMERA_STATUS_NOT_SUPPORTED(-4) ʾ֧ +// 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetAutoConnect)(CameraHandle hCamera,BOOL *pbEnable); + +/******************************************************/ +// : CameraGetReConnectCounts +// : ԶĴǰCameraSetAutoConnect ʹԶܡĬʹܵġ +// : hCamera ľCameraInitá +// puCounts صԶĴ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// ڲֵ֧ͺţú᷵ CAMERA_STATUS_NOT_SUPPORTED(-4) ʾ֧ +// 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetReConnectCounts)( + CameraHandle hCamera, + UINT* puCounts + ); + +/******************************************************/ +// : CameraSetSingleGrabMode +// : ʹܵ֡ץȡģʽ +// : hCamera ľCameraInitá +// bEnable ʹܵ֡ץȡģʽ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// ڲֵ֧ͺţú᷵ CAMERA_STATUS_NOT_SUPPORTED(-4) ʾ֧ +// 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetSingleGrabMode)(CameraHandle hCamera, BOOL bEnable); + +/******************************************************/ +// : CameraGetSingleGrabMode +// : ĵ֡ץȡģʽ +// : hCamera ľCameraInitá +// pbEnable ĵ֡ץȡģʽ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// ڲֵ֧ͺţú᷵ CAMERA_STATUS_NOT_SUPPORTED(-4) ʾ֧ +// 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetSingleGrabMode)(CameraHandle hCamera, BOOL* pbEnable); + +/******************************************************/ +// : CameraRestartGrab +// : ڵ֡ץȡģʽʱÿɹץȡһ֡SDKͣ״̬ô˺ʹSDK˳ͣ״̬ʼץȡһ֡ +// : hCamera ľCameraInitá +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// ڲֵ֧ͺţú᷵ CAMERA_STATUS_NOT_SUPPORTED(-4) ʾ֧ +// 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraRestartGrab)(CameraHandle hCamera); + +/******************************************************/ +// : CameraDrawText +// : ͼл +// : pRgbBuffer ͼݻ +// pFrInfo ͼ֡ͷϢ +// pFontFileName ļ +// FontWidth +// FontHeight ߶ +// pText Ҫ +// (Left, Top, Width, Height) ֵ +// TextColor ɫRGB +// uFlags ־,emCameraDrawTextFlagsеĶ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraDrawText)( + BYTE* pRgbBuffer, + tSdkFrameHead* pFrInfo, + char const* pFontFileName, + UINT FontWidth, + UINT FontHeight, + char const* pText, + INT Left, + INT Top, + UINT Width, + UINT Height, + UINT TextColor, + UINT uFlags + ); + +/******************************************************/ +// : CameraGigeGetIp +// : ȡGIGEIPַ +// : pCameraInfo 豸ϢCameraEnumerateDeviceá +// CamIp IP(ע⣺뱣֤Ļڵ16ֽ) +// CamMask (ע⣺뱣֤Ļڵ16ֽ) +// CamGateWay (ע⣺뱣֤Ļڵ16ֽ) +// EtIp IP(ע⣺뱣֤Ļڵ16ֽ) +// EtMask (ע⣺뱣֤Ļڵ16ֽ) +// EtGateWay (ע⣺뱣֤Ļڵ16ֽ) +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGigeGetIp)( + tSdkCameraDevInfo* pCameraInfo, + char* CamIp, + char* CamMask, + char* CamGateWay, + char* EtIp, + char* EtMask, + char* EtGateWay + ); + +/******************************************************/ +// : CameraGigeSetIp +// : GIGEIPַ +// : pCameraInfo 豸ϢCameraEnumerateDeviceá +// Ip IP(磺192.168.1.100) +// SubMask (磺255.255.255.0) +// GateWay (磺192.168.1.1) +// bPersistent TRUE: Ϊ̶IPFALSEԶIPԲIp, SubMask, GateWay +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGigeSetIp)( + tSdkCameraDevInfo* pCameraInfo, + char const* Ip, + char const* SubMask, + char const* GateWay, + BOOL bPersistent + ); + +/******************************************************/ +// : CameraGigeGetMac +// : ȡGIGEMACַ +// : pCameraInfo 豸ϢCameraEnumerateDeviceá +// CamMac MAC(ע⣺뱣֤Ļڵ18ֽ) +// EtMac MAC(ע⣺뱣֤Ļڵ18ֽ) +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGigeGetMac)( + tSdkCameraDevInfo* pCameraInfo, + char* CamMac, + char* EtMac + ); + +/******************************************************/ +// : CameraEnableFastResponse +// : ʹܿӦ +// : hCamera ľCameraInitá +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraEnableFastResponse)( + CameraHandle hCamera + ); + +/******************************************************/ +// : CameraSetCorrectDeadPixel +// : ʹܻ +// : hCamera ľCameraInitá +// bEnable TRUE: ʹܻ FALSE: رջ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetCorrectDeadPixel)( + CameraHandle hCamera, + BOOL bEnable + ); + +/******************************************************/ +// : CameraGetCorrectDeadPixel +// : ȡʹ״̬ +// : hCamera ľCameraInitá +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetCorrectDeadPixel)( + CameraHandle hCamera, + BOOL* pbEnable + ); + +/******************************************************/ +// : CameraFlatFieldingCorrectSetEnable +// : ʹƽУ +// : hCamera ľCameraInitá +// bEnable TRUE: ʹƽУ FALSE: رƽУ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraFlatFieldingCorrectSetEnable)( + CameraHandle hCamera, + BOOL bEnable + ); + +/******************************************************/ +// : CameraFlatFieldingCorrectGetEnable +// : ȡƽУʹ״̬ +// : hCamera ľCameraInitá +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraFlatFieldingCorrectGetEnable)( + CameraHandle hCamera, + BOOL* pbEnable + ); + +/******************************************************/ +// : CameraFlatFieldingCorrectSetParameter +// : ƽУ +// : hCamera ľCameraInitá +// pDarkFieldingImage ͼƬ +// pDarkFieldingFrInfo ͼƬϢ +// pLightFieldingImage ͼƬ +// pLightFieldingFrInfo ͼƬϢ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraFlatFieldingCorrectSetParameter)( + CameraHandle hCamera, + BYTE const* pDarkFieldingImage, + tSdkFrameHead const* pDarkFieldingFrInfo, + BYTE const* pLightFieldingImage, + tSdkFrameHead const* pLightFieldingFrInfo + ); + +/******************************************************/ +// : CameraFlatFieldingCorrectSaveParameterToFile +// : ƽУļ +// : hCamera ľCameraInitá +// pszFileName ļ· +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraFlatFieldingCorrectSaveParameterToFile)( + CameraHandle hCamera, + char const* pszFileName + ); + +/******************************************************/ +// : CameraFlatFieldingCorrectLoadParameterFromFile +// : ļмƽУ +// : hCamera ľCameraInitá +// pszFileName ļ· +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraFlatFieldingCorrectLoadParameterFromFile)( + CameraHandle hCamera, + char const* pszFileName + ); + +/******************************************************/ +// : CameraCommonCall +// : һЩ⹦ܵãοʱһ㲻Ҫá +// : hCamera ľCameraInitá +// pszCall ܼ +// pszResult ýͬpszCallʱ岻ͬ +// uResultBufSize pszResultָĻֽڴС +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraCommonCall)( + CameraHandle hCamera, + char const* pszCall, + char* pszResult, + UINT uResultBufSize + ); + +/******************************************************/ +// : CameraSetDenoise3DParams +// : 3D +// : hCamera ľCameraInitá +// bEnable û +// nCount ʹüͼƬн(2-8) +// Weights Ȩ +// 統ʹ3ͼƬнԴ3(0.3,0.3,0.4)һͼƬȨشǰ2 +// ҪʹȨأ0ʾͼƬȨͬ(0.33,0.33,0.33) +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetDenoise3DParams)( + CameraHandle hCamera, + BOOL bEnable, + int nCount, + float *Weights + ); + +/******************************************************/ +// : CameraGetDenoise3DParams +// : ȡǰ3D +// : hCamera ľCameraInitá +// bEnable û +// nCount ʹ˼ͼƬн +// bUseWeight Ƿʹ˽Ȩ +// Weights Ȩ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetDenoise3DParams)( + CameraHandle hCamera, + BOOL *bEnable, + int *nCount, + BOOL *bUseWeight, + float *Weights + ); + +/******************************************************/ +// : CameraManualDenoise3D +// : һ֡һν봦 +// : InFramesHead ֡ͷ +// InFramesData ֡ +// nCount ֡ +// Weights Ȩ +// 統ʹ3ͼƬнԴ3(0.3,0.3,0.4)һͼƬȨشǰ2 +// ҪʹȨأ0ʾͼƬȨͬ(0.33,0.33,0.33) +// OutFrameHead ֡ͷ +// OutFrameData ֡ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraManualDenoise3D)( + tSdkFrameHead *InFramesHead, + BYTE **InFramesData, + int nCount, + float *Weights, + tSdkFrameHead *OutFrameHead, + BYTE *OutFrameData + ); + +/******************************************************/ +// : CameraCustomizeDeadPixels +// : 򿪻༭ +// : hCamera ľCameraInitá +// hParent øúĴڵľΪNULL +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraCustomizeDeadPixels)( + CameraHandle hCamera, + HWND hParent + ); + +/******************************************************/ +// : CameraReadDeadPixels +// : ȡ +// : hCamera ľCameraInitá +// pRows y +// pCols x +// pNumPixel ʱʾлĴСʱʾлзصĻ +// pRowspColsΪNULLʱǰĻͨpNumPixel +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraReadDeadPixels)( + CameraHandle hCamera, + USHORT* pRows, + USHORT* pCols, + UINT* pNumPixel + ); + +/******************************************************/ +// : CameraAddDeadPixels +// : +// : hCamera ľCameraInitá +// pRows y +// pCols x +// NumPixel леĻ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraAddDeadPixels)( + CameraHandle hCamera, + USHORT* pRows, + USHORT* pCols, + UINT NumPixel + ); + +/******************************************************/ +// : CameraRemoveDeadPixels +// : ɾָ +// : hCamera ľCameraInitá +// pRows y +// pCols x +// NumPixel леĻ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraRemoveDeadPixels)( + CameraHandle hCamera, + USHORT* pRows, + USHORT* pCols, + UINT NumPixel + ); + +/******************************************************/ +// : CameraRemoveAllDeadPixels +// : ɾл +// : hCamera ľCameraInitá +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraRemoveAllDeadPixels)( + CameraHandle hCamera + ); + +/******************************************************/ +// : CameraSaveDeadPixels +// : 㵽洢 +// : hCamera ľCameraInitá +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSaveDeadPixels)( + CameraHandle hCamera + ); + +/******************************************************/ +// : CameraSaveDeadPixelsToFile +// : 㵽ļ +// : hCamera ľCameraInitá +// sFileName ļ· +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSaveDeadPixelsToFile)( + CameraHandle hCamera, + char const* sFileName + ); + +/******************************************************/ +// : CameraLoadDeadPixelsFromFile +// : ļ +// : hCamera ľCameraInitá +// sFileName ļ· +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraLoadDeadPixelsFromFile)( + CameraHandle hCamera, + char const* sFileName + ); + +/******************************************************/ +// : CameraGetImageBufferPriority +// : һ֡ͼݡΪЧʣSDKͼץȡʱ㿽ƣ +// CameraGetImageBufferʵʻںеһַ +// úɹú󣬱CameraReleaseImageBufferͷ +// CameraGetImageBufferõĻ,Աں˼ʹ +// û +// : hCamera ľCameraInitá +// pFrameInfo ͼ֡ͷϢָ롣 +// pbyBuffer ָͼݵĻָ롣 +// 㿽Чʣ +// ʹһָָָ롣 +// wTimes ץȡͼijʱʱ䡣λ롣 +// wTimesʱڻδͼú +// ᷵سʱϢ +// Priority ȡͼȼ emCameraGetImagePriority +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetImageBufferPriority)( + CameraHandle hCamera, + tSdkFrameHead* pFrameInfo, + BYTE** pbyBuffer, + UINT wTimes, + UINT Priority + ); + +/******************************************************/ +// : CameraGetImageBufferPriorityEx +// : һ֡ͼݡýӿڻõͼǾRGBʽúú +// Ҫ CameraReleaseImageBuffer ͷţҲҪfree֮ĺͷ +// ͷŸúصͼݻ +// : hCamera ľCameraInitá +// piWidth ָ룬ͼĿ +// piHeight ָ룬ͼĸ߶ +// UINT wTimes ץȡͼijʱʱ䡣λ롣 +// wTimesʱڻδͼú +// ᷵سʱϢ +// Priority ȡͼȼ emCameraGetImagePriority +// ֵ : ɹʱRGBݻ׵ַ; +// 򷵻0 +/******************************************************/ +typedef unsigned char* (__stdcall *_CameraGetImageBufferPriorityEx)( + CameraHandle hCamera, + INT* piWidth, + INT* piHeight, + UINT wTimes, + UINT Priority + ); + +/******************************************************/ +// : CameraGetImageBufferPriorityEx2 +// : һ֡ͼݡýӿڻõͼǾRGBʽúú +// Ҫ CameraReleaseImageBuffer ͷţҲҪfree֮ĺͷ +// ͷŸúصͼݻ +// : hCamera ľCameraInitá +// pImageData ͼݵĻСuOutFormatָĸʽƥ䣬ݻ +// piWidth ָ룬ͼĿ +// piHeight ָ룬ͼĸ߶ +// wTimes ץȡͼijʱʱ䡣λ롣 +// wTimesʱڻδͼú +// ᷵سʱϢ +// Priority ȡͼȼ emCameraGetImagePriority +// ֵ : ɹʱRGBݻ׵ַ; +// 򷵻0 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetImageBufferPriorityEx2)( + CameraHandle hCamera, + BYTE* pImageData, + UINT uOutFormat, + int* piWidth, + int* piHeight, + UINT wTimes, + UINT Priority + ); + +/******************************************************/ +// : CameraGetImageBufferPriorityEx3 +// : һ֡ͼݡýӿڻõͼǾRGBʽúú +// Ҫ CameraReleaseImageBuffer ͷ. +// uOutFormat 0 : 8 BIT gray 1:rgb24 2:rgba32 3:bgr24 4:bgra32 +// : hCamera ľCameraInitá +// pImageData ͼݵĻСuOutFormatָĸʽƥ䣬ݻ +// piWidth ָ룬ͼĿ +// piHeight ָ룬ͼĸ߶ +// puTimeStamp ޷Σͼʱ +// UINT wTimes ץȡͼijʱʱ䡣λ롣 +// wTimes ʱڻδͼú᷵سʱϢ +// Priority ȡͼȼ emCameraGetImagePriority +// ֵ : ɹʱRGBݻ׵ַ; +// 򷵻0 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetImageBufferPriorityEx3)( + CameraHandle hCamera, + BYTE*pImageData, + UINT uOutFormat, + int *piWidth, + int *piHeight, + UINT* puTimeStamp, + UINT wTimes, + UINT Priority + ); + +/******************************************************/ +// : CameraClearBuffer +// : ѻ֡ +// : hCamera ľCameraInitá +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraClearBuffer)( + CameraHandle hCamera + ); + +/******************************************************/ +// : CameraSoftTriggerEx +// : ִһִк󣬻ᴥCameraSetTriggerCount +// ָ֡ +// : hCamera ľCameraInitá +// uFlags ܱ־,emCameraSoftTriggerExFlagsеĶ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSoftTriggerEx)( + CameraHandle hCamera, + UINT uFlags + ); + +/******************************************************/ +// : CameraSetHDR +// : HDRҪ֧֣HDRܵͺţ˺ش룬ʾ֧֡ +// : hCamera ľCameraInitá +// value HDRϵΧ0.01.0 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// 򷵻 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetHDR)( + CameraHandle hCamera, + float value + ); + +/******************************************************/ +// : CameraGetHDR +// : ȡHDRҪ֧֣HDRܵͺţ˺ش룬ʾ֧֡ +// : hCamera ľCameraInitá +// value HDRϵΧ0.01.0 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// 򷵻 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetHDR)( + CameraHandle hCamera, + float* value + ); + +/******************************************************/ +// : CameraGetFrameID +// : ȡǰ֡ID֧(ȫϵ֧)˺ش룬ʾ֧֡ +// : hCamera ľCameraInitá +// id ֡ID +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// 򷵻 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetFrameID)( + CameraHandle hCamera, + UINT* id + ); + +/******************************************************/ +// : CameraGetFrameTimeStamp +// : ȡǰ֡ʱ(λ΢) +// : hCamera ľCameraInitá +// TimeStampL ʱ32λ +// TimeStampH ʱ32λ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// 򷵻 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetFrameTimeStamp)( + CameraHandle hCamera, + UINT* TimeStampL, + UINT* TimeStampH + ); + +/******************************************************/ +// : CameraSetHDRGainMode +// : ģʽҪ֧֣ģʽлܵͺţ˺ش룬ʾ֧֡ +// : hCamera ľCameraInitá +// value 0 1 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// 򷵻 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetHDRGainMode)( + CameraHandle hCamera, + int value + ); + +/******************************************************/ +// : CameraGetHDRGainMode +// : ȡģʽҪ֧֣ģʽлܵͺţ˺ش룬ʾ֧֡ +// : hCamera ľCameraInitá +// value 0 1 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0)ʾ״̬; +// 򷵻 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGetHDRGainMode)( + CameraHandle hCamera, + int* value + ); + +/******************************************************/ +// : CameraCreateDIBitmap +// : ֡ݴHBITMAP +// : hDC: Handle to a device contextWIN32 API CreateDIBitmapIJhdc +// pFrameBuffer: ֡ +// pFrameHead: ֡ͷ +// outBitmap: ´HBITMAPʹҪWIN32 API DeleteObjectͷţ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0) +// 򷵻 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraCreateDIBitmap)( + HDC hDC, + BYTE *pFrameBuffer, + tSdkFrameHead* pFrameHead, + HBITMAP* outBitmap + ); + +/******************************************************/ +// : CameraDrawFrameBuffer +// : ָ֡ +// : pFrameBuffer: ֡ +// pFrameHead: ֡ͷ +// hWnd: ĿĴ +// Algorithm 㷨 0ٵԲ 1ٶ +// Mode ģʽ 0: ȱ 1 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0) +// 򷵻 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraDrawFrameBuffer)( + BYTE *pFrameBuffer, + tSdkFrameHead* pFrameHead, + HWND hWnd, + int Algorithm, + int Mode + ); + +/******************************************************/ +// : CameraFlipFrameBuffer +// : ת֡ +// : pFrameBuffer: ֡ +// pFrameHead: ֡ͷ +// Flags: 1: 2 3¡ҽһηת(൱ת180) +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0) +// 򷵻 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraFlipFrameBuffer)( + BYTE *pFrameBuffer, + tSdkFrameHead* pFrameHead, + int Flags + ); + +/******************************************************/ +// : CameraConvertFrameBufferFormat +// : ת֡ݸʽ +// : hCamera: +// pInFrameBuffer: ֡ +// pOutFrameBuffer: ֡ +// outWidth: +// outHeight: ߶ +// outMediaType: ʽ +// pFrameHead: ֡ͷϢתɹϢᱻ޸Ϊ֡Ϣ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0) +// 򷵻 0ֵοCameraStatus.hдĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraConvertFrameBufferFormat)( + CameraHandle hCamera, + BYTE *pInFrameBuffer, + BYTE *pOutFrameBuffer, + int outWidth, + int outHeight, + UINT outMediaType, + tSdkFrameHead* pFrameHead + ); + +/******************************************************/ +// : CameraSetConnectionStatusCallback +// : ״̬ıĻص֪ͨߡʱ +// pCallBackָĻصͻᱻá +// : hCamera ľCameraInitá +// pCallBack صָ롣 +// pContext صĸӲڻصʱ +// øӲᱻ룬ΪNULL +// ʱЯϢ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetConnectionStatusCallback)( + CameraHandle hCamera, + CAMERA_CONNECTION_STATUS_CALLBACK pCallBack, + PVOID pContext + ); + +/******************************************************/ +// : CameraSetLightingControllerMode +// : ùԴģʽϵҪӲ֧֣ +// : hCamera ľCameraInitá +// index +// mode ģʽ0: 1:ֶ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetLightingControllerMode)( + CameraHandle hCamera, + int index, + int mode + ); + +/******************************************************/ +// : CameraSetLightingControllerState +// : ùԴ״̬ϵҪӲ֧֣ +// : hCamera ľCameraInitá +// index +// state ״̬0:ر 1򿪣 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraSetLightingControllerState)( + CameraHandle hCamera, + int index, + int state + ); + +typedef CameraSdkStatus (__stdcall *_CameraGetEyeCount)( + CameraHandle hCamera, + int* EyeCount + ); + +typedef CameraSdkStatus (__stdcall *_CameraMultiEyeImageProcess)( + CameraHandle hCamera, + int iEyeIndex, + BYTE* pbyIn, + tSdkFrameHead* pInFrInfo, + BYTE* pbyOut, + tSdkFrameHead* pOutFrInfo, + UINT uOutFormat, + UINT uReserved + ); + +/******************************************************/ +// : CameraGrabber_CreateFromDevicePage +// : бûѡҪ򿪵 +// : ִгɹغGrabber +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGrabber_CreateFromDevicePage)( + void** Grabber + ); + +/******************************************************/ +// : CameraGrabber_CreateByIndex +// : ʹбGrabber +// : Grabber ִгɹغGrabber +// Index +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGrabber_CreateByIndex)( + void** Grabber, + int Index + ); + +/******************************************************/ +// : CameraGrabber_CreateByName +// : ʹƴGrabber +// : Grabber ִгɹغGrabber +// Name +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGrabber_CreateByName)( + void** Grabber, + char* Name + ); + +/******************************************************/ +// : CameraGrabber_Create +// : 豸ϢGrabber +// : Grabber ִгɹغGrabber +// pDevInfo 豸ϢCameraEnumerateDeviceá +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGrabber_Create)( + void** Grabber, + tSdkCameraDevInfo* pDevInfo + ); + +/******************************************************/ +// : CameraGrabber_Destroy +// : Grabber +// : Grabber +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGrabber_Destroy)( + void* Grabber + ); + +/******************************************************/ +// : CameraGrabber_SetHWnd +// : ԤƵʾ +// : Grabber +// hWnd ھ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGrabber_SetHWnd)( + void* Grabber, + HWND hWnd + ); + +/******************************************************/ +// : CameraGrabber_SetPriority +// : ȡͼʹõȼ +// : Grabber +// Priority ȡͼȼ emCameraGetImagePriority +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGrabber_SetPriority)( + void* Grabber, + UINT Priority + ); + +/******************************************************/ +// : CameraGrabber_StartLive +// : Ԥ +// : Grabber +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGrabber_StartLive)( + void* Grabber + ); + +/******************************************************/ +// : CameraGrabber_StopLive +// : ֹͣԤ +// : Grabber +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGrabber_StopLive)( + void* Grabber + ); + +/******************************************************/ +// : CameraGrabber_SaveImage +// : ץͼ +// : Grabber +// Image ץȡͼҪCameraImage_Destroyͷţ +// TimeOut ʱʱ䣨룩 +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGrabber_SaveImage)( + void* Grabber, + void** Image, + DWORD TimeOut + ); + +/******************************************************/ +// : CameraGrabber_SaveImageAsync +// : ύһ첽ץͼύɹץͼɻصûõɺ +// : Grabber +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGrabber_SaveImageAsync)( + void* Grabber + ); + +/******************************************************/ +// : CameraGrabber_SaveImageAsyncEx +// : ύһ첽ץͼύɹץͼɻصûõɺ +// : Grabber +// UserData ʹCameraImage_GetUserDataImageȡֵ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGrabber_SaveImageAsyncEx)( + void* Grabber, + void* UserData + ); + +/******************************************************/ +// : CameraGrabber_SetSaveImageCompleteCallback +// : 첽ʽץͼɺ +// : Grabber +// Callback ץͼʱ +// Context CallbackʱΪCallback +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGrabber_SetSaveImageCompleteCallback)( + void* Grabber, + pfnCameraGrabberSaveImageComplete Callback, + void* Context + ); + +/******************************************************/ +// : CameraGrabber_SetFrameListener +// : ֡ +// : Grabber +// Listener ˺0ʾǰ֡ +// Context ListenerʱΪListener +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGrabber_SetFrameListener)( + void* Grabber, + pfnCameraGrabberFrameListener Listener, + void* Context + ); + +/******************************************************/ +// : CameraGrabber_SetRawCallback +// : RAWص +// : Grabber +// Callback Rawص +// Context CallbackʱΪCallback +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGrabber_SetRawCallback)( + void* Grabber, + pfnCameraGrabberFrameCallback Callback, + void* Context + ); + +/******************************************************/ +// : CameraGrabber_SetRGBCallback +// : RGBص +// : Grabber +// Callback RGBص +// Context CallbackʱΪCallback +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGrabber_SetRGBCallback)( + void* Grabber, + pfnCameraGrabberFrameCallback Callback, + void* Context + ); + +/******************************************************/ +// : CameraGrabber_GetCameraHandle +// : ȡ +// : Grabber +// hCamera ص +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGrabber_GetCameraHandle)( + void* Grabber, + CameraHandle *hCamera + ); + +/******************************************************/ +// : CameraGrabber_GetStat +// : ȡ֡ͳϢ +// : Grabber +// stat صͳϢ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGrabber_GetStat)( + void* Grabber, + tSdkGrabberStat *stat + ); + +/******************************************************/ +// : CameraGrabber_GetCameraDevInfo +// : ȡDevInfo +// : Grabber +// DevInfo صDevInfo +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraGrabber_GetCameraDevInfo)( + void* Grabber, + tSdkCameraDevInfo *DevInfo + ); + +/******************************************************/ +// : CameraImage_Create +// : һµImage +// : Image +// pFrameBuffer ֡ݻ +// pFrameHead ֡ͷ +// bCopy TRUE: Ƴһµ֡ FALSE: ƣֱʹpFrameBufferָĻ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraImage_Create)( + void** Image, + BYTE *pFrameBuffer, + tSdkFrameHead* pFrameHead, + BOOL bCopy + ); + +/******************************************************/ +// : CameraImage_Destroy +// : Image +// : Image +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraImage_Destroy)( + void* Image + ); + +/******************************************************/ +// : CameraImage_GetData +// : ȡImage +// : Image +// DataBuffer ͼ +// Head ͼϢ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraImage_GetData)( + void* Image, + BYTE** DataBuffer, + tSdkFrameHead** Head + ); + +/******************************************************/ +// : CameraImage_GetUserData +// : ȡImageûԶ +// : Image +// UserData ûԶ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraImage_GetUserData)( + void* Image, + void** UserData + ); + +/******************************************************/ +// : CameraImage_SetUserData +// : ImageûԶ +// : Image +// UserData ûԶ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraImage_SetUserData)( + void* Image, + void* UserData + ); + +/******************************************************/ +// : CameraImage_IsEmpty +// : жһImageǷΪ +// : Image +// IsEmpty Ϊշ:TRUE(1) 򷵻:FALSE(0) +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraImage_IsEmpty)( + void* Image, + BOOL* IsEmpty + ); + +/******************************************************/ +// : CameraImage_Draw +// : Imageָ +// : Image +// hWnd ĿĴ +// Algorithm 㷨 0ٵԲ 1ٶ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraImage_Draw)( + void* Image, + HWND hWnd, + int Algorithm + ); + +/******************************************************/ +// : CameraImage_BitBlt +// : Imageָڣţ +// : Image +// hWnd ĿĴ +// xDst,yDst: ĿεϽ +// cxDst,cyDst: ĿεĿ +// xSrc,ySrc: ͼεϽ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraImage_BitBlt)( + void* Image, + HWND hWnd, + int xDst, + int yDst, + int cxDst, + int cyDst, + int xSrc, + int ySrc + ); + +/******************************************************/ +// : CameraImage_SaveAsBmp +// : bmpʽImage +// : Image +// FileName ļ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraImage_SaveAsBmp)( + void* Image, + char const* FileName + ); + +/******************************************************/ +// : CameraImage_SaveAsJpeg +// : jpgʽImage +// : Image +// FileName ļ +// Quality (1-100)100ΪѵļҲ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraImage_SaveAsJpeg)( + void* Image, + char const* FileName, + BYTE Quality + ); + +/******************************************************/ +// : CameraImage_SaveAsPng +// : pngʽImage +// : Image +// FileName ļ +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraImage_SaveAsPng)( + void* Image, + char const* FileName + ); + +/******************************************************/ +// : CameraImage_SaveAsRaw +// : raw Image +// : Image +// FileName ļ +// Format 0: 8Bit Raw 1: 16Bit Raw +// ֵ : ɹʱCAMERA_STATUS_SUCCESS (0); +// 򷵻ط0ֵĴ,οCameraStatus.h +// дĶ塣 +/******************************************************/ +typedef CameraSdkStatus (__stdcall *_CameraImage_SaveAsRaw)( + void* Image, + char const* FileName, + int Format + ); + + +#ifdef API_LOAD_MAIN +#define EXTERN +#else +#define EXTERN extern +#endif + +EXTERN INT gSdkLanguageSel;//0:English 1:Chinese + +EXTERN _CameraSdkInit CameraSdkInit; + +EXTERN _CameraSetCallbackFunction CameraSetCallbackFunction; + +EXTERN _CameraGetInformation CameraGetInformation; + +EXTERN _CameraSaveImage CameraSaveImage; + +EXTERN _CameraInitRecord CameraInitRecord; + +EXTERN _CameraStopRecord CameraStopRecord; + +EXTERN _CameraPushFrame CameraPushFrame; + +EXTERN _CameraSpecialControl CameraSpecialControl; + +EXTERN _CameraSnapToBuffer CameraSnapToBuffer; + +EXTERN _CameraIsOpened CameraIsOpened; + +EXTERN _CameraInit CameraInit; + +EXTERN _CameraInitEx CameraInitEx; + +EXTERN _CameraInitEx2 CameraInitEx2; + +EXTERN _CameraUnInit CameraUnInit; + +EXTERN _CameraPlay CameraPlay; + +EXTERN _CameraPause CameraPause; + +EXTERN _CameraStop CameraStop; + +EXTERN _CameraSetDisplayMode CameraSetDisplayMode; + +EXTERN _CameraDisplayRGB24 CameraDisplayRGB24; + +EXTERN _CameraSetDisplayOffset CameraSetDisplayOffset; + +EXTERN _CameraImageOverlay CameraImageOverlay; + +EXTERN _CameraDisplayInit CameraDisplayInit; + +EXTERN _CameraDisplayInitEx CameraDisplayInitEx; + +EXTERN _CameraSetDisplaySize CameraSetDisplaySize; + +EXTERN _CameraGetImageBuffer CameraGetImageBuffer; + +EXTERN _CameraGetImageBufferEx CameraGetImageBufferEx; + +EXTERN _CameraReleaseImageBuffer CameraReleaseImageBuffer; + +EXTERN _CameraCreateSettingPage CameraCreateSettingPage; + +EXTERN _CameraSetActiveSettingSubPage CameraSetActiveSettingSubPage; + +EXTERN _CameraSetSettingPageParent CameraSetSettingPageParent; + +EXTERN _CameraGetSettingPageHWnd CameraGetSettingPageHWnd; + +EXTERN _CameraCustomizeResolution CameraCustomizeResolution; + +EXTERN _CameraSetMirror CameraSetMirror; + +EXTERN _CameraGetMirror CameraGetMirror; + +EXTERN _CameraSetRotate CameraSetRotate; + +EXTERN _CameraGetRotate CameraGetRotate; + +EXTERN _CameraSetMonochrome CameraSetMonochrome; + +EXTERN _CameraGetMonochrome CameraGetMonochrome; + +EXTERN _CameraSetInverse CameraSetInverse; + +EXTERN _CameraGetInverse CameraGetInverse; + +EXTERN _CameraGetImageResolution CameraGetImageResolution; + +EXTERN _CameraGetImageResolutionEx CameraGetImageResolutionEx; + +EXTERN _CameraSetImageResolution CameraSetImageResolution; + +EXTERN _CameraSetImageResolutionEx CameraSetImageResolutionEx; + +EXTERN _CameraGetMediaType CameraGetMediaType; + +EXTERN _CameraSetMediaType CameraSetMediaType; + +EXTERN _CameraSetAeState CameraSetAeState; + +EXTERN _CameraGetAeState CameraGetAeState; + +EXTERN _CameraSetAeTarget CameraSetAeTarget; + +EXTERN _CameraGetAeTarget CameraGetAeTarget; + +EXTERN _CameraSetAeExposureRange CameraSetAeExposureRange; + +EXTERN _CameraGetAeExposureRange CameraGetAeExposureRange; + +EXTERN _CameraSetAeAnalogGainRange CameraSetAeAnalogGainRange; + +EXTERN _CameraGetAeAnalogGainRange CameraGetAeAnalogGainRange; + +EXTERN _CameraSetAeThreshold CameraSetAeThreshold; + +EXTERN _CameraGetAeThreshold CameraGetAeThreshold; + +EXTERN _CameraSetExposureTime CameraSetExposureTime; + +EXTERN _CameraGetExposureTime CameraGetExposureTime; + +EXTERN _CameraGetExposureTimeRange CameraGetExposureTimeRange; + +EXTERN _CameraGetExposureLineTime CameraGetExposureLineTime; + +EXTERN _CameraSetAnalogGain CameraSetAnalogGain; + +EXTERN _CameraGetAnalogGain CameraGetAnalogGain; + +EXTERN _CameraSetSharpness CameraSetSharpness; + +EXTERN _CameraGetSharpness CameraGetSharpness; + +EXTERN _CameraGetPresetClrTemp CameraGetPresetClrTemp; + +EXTERN _CameraSetPresetClrTemp CameraSetPresetClrTemp; + +EXTERN _CameraSetUserClrTempGain CameraSetUserClrTempGain; + +EXTERN _CameraGetUserClrTempGain CameraGetUserClrTempGain; + +EXTERN _CameraSetUserClrTempMatrix CameraSetUserClrTempMatrix; + +EXTERN _CameraGetUserClrTempMatrix CameraGetUserClrTempMatrix; + +EXTERN _CameraSetClrTempMode CameraSetClrTempMode; + +EXTERN _CameraGetClrTempMode CameraGetClrTempMode; + +EXTERN _CameraSetLutMode CameraSetLutMode; + +EXTERN _CameraGetLutMode CameraGetLutMode; + +EXTERN _CameraSelectLutPreset CameraSelectLutPreset; + +EXTERN _CameraGetLutPresetSel CameraGetLutPresetSel; + +EXTERN _CameraSetCustomLut CameraSetCustomLut; + +EXTERN _CameraGetCustomLut CameraGetCustomLut; + +EXTERN _CameraGetCurrentLut CameraGetCurrentLut; + +EXTERN _CameraSetOnceWB CameraSetOnceWB; + +EXTERN _CameraSetOnceBB CameraSetOnceBB; + +EXTERN _CameraSetWbMode CameraSetWbMode; + +EXTERN _CameraGetWbMode CameraGetWbMode; + +EXTERN _CameraSetWbWindow CameraSetWbWindow; + +EXTERN _CameraSetGain CameraSetGain; + +EXTERN _CameraGetGain CameraGetGain; + +EXTERN _CameraSetGamma CameraSetGamma; + +EXTERN _CameraGetGamma CameraGetGamma; + +EXTERN _CameraSetSaturation CameraSetSaturation; + +EXTERN _CameraGetSaturation CameraGetSaturation; + +EXTERN _CameraSetContrast CameraSetContrast; + +EXTERN _CameraGetContrast CameraGetContrast; + +EXTERN _CameraSetFrameSpeed CameraSetFrameSpeed; + +EXTERN _CameraGetFrameSpeed CameraGetFrameSpeed; + +EXTERN _CameraSetAntiFlick CameraSetAntiFlick; + +EXTERN _CameraGetAntiFlick CameraGetAntiFlick; + +EXTERN _CameraGetLightFrequency CameraGetLightFrequency; + +EXTERN _CameraSetLightFrequency CameraSetLightFrequency; + +EXTERN _CameraSetTransPackLen CameraSetTransPackLen; + +EXTERN _CameraGetTransPackLen CameraGetTransPackLen; + +EXTERN _CameraWriteSN CameraWriteSN; + +EXTERN _CameraReadSN CameraReadSN; + +EXTERN _CameraSaveParameter CameraSaveParameter; + +EXTERN _CameraLoadParameter CameraLoadParameter; + +EXTERN _CameraGetCurrentParameterGroup CameraGetCurrentParameterGroup; + +EXTERN _CameraEnumerateDevice CameraEnumerateDevice; + +EXTERN _CameraEnumerateDeviceEx CameraEnumerateDeviceEx; + +EXTERN _CameraGetCapability CameraGetCapability; + +EXTERN _CameraImageProcess CameraImageProcess; + +EXTERN _CameraImageProcessEx CameraImageProcessEx; + +EXTERN _CameraSoftTrigger CameraSoftTrigger; + +EXTERN _CameraSetTriggerMode CameraSetTriggerMode; + +EXTERN _CameraGetTriggerMode CameraGetTriggerMode; + +EXTERN _CameraSetStrobeMode CameraSetStrobeMode; + +EXTERN _CameraGetStrobeMode CameraGetStrobeMode; + +EXTERN _CameraSetStrobeDelayTime CameraSetStrobeDelayTime; + +EXTERN _CameraGetStrobeDelayTime CameraGetStrobeDelayTime; + +EXTERN _CameraSetStrobePulseWidth CameraSetStrobePulseWidth; + +EXTERN _CameraGetStrobePulseWidth CameraGetStrobePulseWidth; + +EXTERN _CameraSetStrobePolarity CameraSetStrobePolarity; + +EXTERN _CameraGetStrobePolarity CameraGetStrobePolarity; + +EXTERN _CameraSetExtTrigSignalType CameraSetExtTrigSignalType; + +EXTERN _CameraGetExtTrigSignalType CameraGetExtTrigSignalType; + +EXTERN _CameraSetExtTrigShutterType CameraSetExtTrigShutterType; + +EXTERN _CameraGetExtTrigShutterType CameraGetExtTrigShutterType; + +EXTERN _CameraSetExtTrigDelayTime CameraSetExtTrigDelayTime; + +EXTERN _CameraGetExtTrigDelayTime CameraGetExtTrigDelayTime; + +EXTERN _CameraSetExtTrigJitterTime CameraSetExtTrigJitterTime; + +EXTERN _CameraGetExtTrigJitterTime CameraGetExtTrigJitterTime; + +EXTERN _CameraGetExtTrigCapability CameraGetExtTrigCapability; + +EXTERN _CameraPauseLevelTrigger CameraPauseLevelTrigger; + +EXTERN _CameraShowSettingPage CameraShowSettingPage; + +EXTERN _CameraGetFrameStatistic CameraGetFrameStatistic; + +EXTERN _CameraGetResolutionForSnap CameraGetResolutionForSnap; + +EXTERN _CameraSetResolutionForSnap CameraSetResolutionForSnap; + +EXTERN _CameraIsAeWinVisible CameraIsAeWinVisible; + +EXTERN _CameraIsWbWinVisible CameraIsWbWinVisible; + +EXTERN _CameraGetNoiseFilterState CameraGetNoiseFilterState; + +EXTERN _CameraSetParameterMode CameraSetParameterMode; + +EXTERN _CameraGetParameterMode CameraGetParameterMode; + +EXTERN _CameraSetParameterMask CameraSetParameterMask; + +EXTERN _CameraGetTriggerCount CameraGetTriggerCount; + +EXTERN _CameraGetCrossLine CameraGetCrossLine; + +EXTERN _CameraSetCrossLine CameraSetCrossLine; + +EXTERN _CameraGetTriggerDelayTime CameraGetTriggerDelayTime; + +EXTERN _CameraSetTriggerDelayTime CameraSetTriggerDelayTime; + +EXTERN _CameraSetAeWinVisible CameraSetAeWinVisible; + +EXTERN _CameraSetNoiseFilter CameraSetNoiseFilter; + +EXTERN _CameraSetTriggerCount CameraSetTriggerCount; + +EXTERN _CameraCustomizeReferWin CameraCustomizeReferWin; + +EXTERN _CameraSetAeWindow CameraSetAeWindow; + +EXTERN _CameraReadParameterFromFile CameraReadParameterFromFile; + +EXTERN _CameraSetWbWinVisible CameraSetWbWinVisible; + +EXTERN _CameraRstTimeStamp CameraRstTimeStamp; + +EXTERN _CameraGetCapabilityEx CameraGetCapabilityEx; + +EXTERN _CameraSaveUserData CameraSaveUserData; + +EXTERN _CameraLoadUserData CameraLoadUserData; + +EXTERN _CameraGetFriendlyName CameraGetFriendlyName; + +EXTERN _CameraSetFriendlyName CameraSetFriendlyName; + +EXTERN _CameraSdkGetVersionString CameraSdkGetVersionString; + +EXTERN _CameraCheckFwUpdate CameraCheckFwUpdate; + +EXTERN _CameraGetFirmwareVersion CameraGetFirmwareVersion; + +EXTERN _CameraGetFirmwareVision CameraGetFirmwareVision; + +EXTERN _CameraGetEnumInfo CameraGetEnumInfo; + +EXTERN _CameraGetInerfaceVersion CameraGetInerfaceVersion; + +EXTERN _CameraSetIOState CameraSetIOState; + +EXTERN _CameraGetIOState CameraGetIOState; + +EXTERN _CameraSetInPutIOMode CameraSetInPutIOMode; + +EXTERN _CameraSetOutPutIOMode CameraSetOutPutIOMode; + +EXTERN _CameraSetOutPutPWM CameraSetOutPutPWM; + +EXTERN _CameraSetBayerDecAlgorithm CameraSetBayerDecAlgorithm; + +EXTERN _CameraGetBayerDecAlgorithm CameraGetBayerDecAlgorithm; + +EXTERN _CameraSetBlackLevel CameraSetBlackLevel; + +EXTERN _CameraGetBlackLevel CameraGetBlackLevel; + +EXTERN _CameraSetWhiteLevel CameraSetWhiteLevel; + +EXTERN _CameraGetWhiteLevel CameraGetWhiteLevel; + +EXTERN _CameraSetIspOutFormat CameraSetIspOutFormat; + +EXTERN _CameraGetIspOutFormat CameraGetIspOutFormat; + +EXTERN _CameraGetErrorString CameraGetErrorString; + +EXTERN _CameraGetCapabilityEx2 CameraGetCapabilityEx2; + +EXTERN _CameraGetImageBufferEx2 CameraGetImageBufferEx2; + +EXTERN _CameraGetImageBufferEx3 CameraGetImageBufferEx3; + +EXTERN _CameraReConnect CameraReConnect; + +EXTERN _CameraConnectTest CameraConnectTest; + +EXTERN _CameraSetLedEnable CameraSetLedEnable; + +EXTERN _CameraGetLedEnable CameraGetLedEnable; + +EXTERN _CameraSetLedOnOff CameraSetLedOnOff; + +EXTERN _CameraGetLedOnOff CameraGetLedOnOff; + +EXTERN _CameraSetLedDuration CameraSetLedDuration; + +EXTERN _CameraGetLedDuration CameraGetLedDuration; + +EXTERN _CameraSetLedBrightness CameraSetLedBrightness; + +EXTERN _CameraGetLedBrightness CameraGetLedBrightness; + +EXTERN _CameraEnableTransferRoi CameraEnableTransferRoi; + +EXTERN _CameraSetTransferRoi CameraSetTransferRoi; + +EXTERN _CameraGetTransferRoi CameraGetTransferRoi; + +EXTERN _CameraAlignMalloc CameraAlignMalloc; + +EXTERN _CameraAlignFree CameraAlignFree; + +EXTERN _CameraSetAutoConnect CameraSetAutoConnect; + +EXTERN _CameraGetAutoConnect CameraGetAutoConnect; + +EXTERN _CameraGetReConnectCounts CameraGetReConnectCounts; + +EXTERN _CameraSetSingleGrabMode CameraSetSingleGrabMode; + +EXTERN _CameraGetSingleGrabMode CameraGetSingleGrabMode; + +EXTERN _CameraRestartGrab CameraRestartGrab; + +EXTERN _CameraDrawText CameraDrawText; + +EXTERN _CameraGigeGetIp CameraGigeGetIp; + +EXTERN _CameraGigeSetIp CameraGigeSetIp; + +EXTERN _CameraGigeGetMac CameraGigeGetMac; + +EXTERN _CameraEnableFastResponse CameraEnableFastResponse; + +EXTERN _CameraSetCorrectDeadPixel CameraSetCorrectDeadPixel; + +EXTERN _CameraGetCorrectDeadPixel CameraGetCorrectDeadPixel; + +EXTERN _CameraFlatFieldingCorrectSetEnable CameraFlatFieldingCorrectSetEnable; + +EXTERN _CameraFlatFieldingCorrectGetEnable CameraFlatFieldingCorrectGetEnable; + +EXTERN _CameraFlatFieldingCorrectSetParameter CameraFlatFieldingCorrectSetParameter; + +EXTERN _CameraFlatFieldingCorrectSaveParameterToFile CameraFlatFieldingCorrectSaveParameterToFile; + +EXTERN _CameraFlatFieldingCorrectLoadParameterFromFile CameraFlatFieldingCorrectLoadParameterFromFile; + +EXTERN _CameraCommonCall CameraCommonCall; + +EXTERN _CameraSetDenoise3DParams CameraSetDenoise3DParams; + +EXTERN _CameraGetDenoise3DParams CameraGetDenoise3DParams; + +EXTERN _CameraManualDenoise3D CameraManualDenoise3D; + +EXTERN _CameraCustomizeDeadPixels CameraCustomizeDeadPixels; + +EXTERN _CameraReadDeadPixels CameraReadDeadPixels; + +EXTERN _CameraAddDeadPixels CameraAddDeadPixels; + +EXTERN _CameraRemoveDeadPixels CameraRemoveDeadPixels; + +EXTERN _CameraRemoveAllDeadPixels CameraRemoveAllDeadPixels; + +EXTERN _CameraSaveDeadPixels CameraSaveDeadPixels; + +EXTERN _CameraSaveDeadPixelsToFile CameraSaveDeadPixelsToFile; + +EXTERN _CameraLoadDeadPixelsFromFile CameraLoadDeadPixelsFromFile; + +EXTERN _CameraGetImageBufferPriority CameraGetImageBufferPriority; + +EXTERN _CameraGetImageBufferPriorityEx CameraGetImageBufferPriorityEx; + +EXTERN _CameraGetImageBufferPriorityEx2 CameraGetImageBufferPriorityEx2; + +EXTERN _CameraGetImageBufferPriorityEx3 CameraGetImageBufferPriorityEx3; + +EXTERN _CameraClearBuffer CameraClearBuffer; + +EXTERN _CameraSoftTriggerEx CameraSoftTriggerEx; + +EXTERN _CameraSetHDR CameraSetHDR; + +EXTERN _CameraGetHDR CameraGetHDR; + +EXTERN _CameraGetFrameID CameraGetFrameID; + +EXTERN _CameraGetFrameTimeStamp CameraGetFrameTimeStamp; + +EXTERN _CameraSetHDRGainMode CameraSetHDRGainMode; + +EXTERN _CameraGetHDRGainMode CameraGetHDRGainMode; + +EXTERN _CameraCreateDIBitmap CameraCreateDIBitmap; + +EXTERN _CameraDrawFrameBuffer CameraDrawFrameBuffer; + +EXTERN _CameraFlipFrameBuffer CameraFlipFrameBuffer; + +EXTERN _CameraConvertFrameBufferFormat CameraConvertFrameBufferFormat; + +EXTERN _CameraSetConnectionStatusCallback CameraSetConnectionStatusCallback; + +EXTERN _CameraSetLightingControllerMode CameraSetLightingControllerMode; + +EXTERN _CameraSetLightingControllerState CameraSetLightingControllerState; + +EXTERN _CameraGetEyeCount CameraGetEyeCount; + +EXTERN _CameraMultiEyeImageProcess CameraMultiEyeImageProcess; + +EXTERN _CameraGrabber_CreateFromDevicePage CameraGrabber_CreateFromDevicePage; + +EXTERN _CameraGrabber_CreateByIndex CameraGrabber_CreateByIndex; + +EXTERN _CameraGrabber_CreateByName CameraGrabber_CreateByName; + +EXTERN _CameraGrabber_Create CameraGrabber_Create; + +EXTERN _CameraGrabber_Destroy CameraGrabber_Destroy; + +EXTERN _CameraGrabber_SetHWnd CameraGrabber_SetHWnd; + +EXTERN _CameraGrabber_SetPriority CameraGrabber_SetPriority; + +EXTERN _CameraGrabber_StartLive CameraGrabber_StartLive; + +EXTERN _CameraGrabber_StopLive CameraGrabber_StopLive; + +EXTERN _CameraGrabber_SaveImage CameraGrabber_SaveImage; + +EXTERN _CameraGrabber_SaveImageAsync CameraGrabber_SaveImageAsync; + +EXTERN _CameraGrabber_SaveImageAsyncEx CameraGrabber_SaveImageAsyncEx; + +EXTERN _CameraGrabber_SetSaveImageCompleteCallback CameraGrabber_SetSaveImageCompleteCallback; + +EXTERN _CameraGrabber_SetFrameListener CameraGrabber_SetFrameListener; + +EXTERN _CameraGrabber_SetRawCallback CameraGrabber_SetRawCallback; + +EXTERN _CameraGrabber_SetRGBCallback CameraGrabber_SetRGBCallback; + +EXTERN _CameraGrabber_GetCameraHandle CameraGrabber_GetCameraHandle; + +EXTERN _CameraGrabber_GetStat CameraGrabber_GetStat; + +EXTERN _CameraGrabber_GetCameraDevInfo CameraGrabber_GetCameraDevInfo; + +EXTERN _CameraImage_Create CameraImage_Create; + +EXTERN _CameraImage_Destroy CameraImage_Destroy; + +EXTERN _CameraImage_GetData CameraImage_GetData; + +EXTERN _CameraImage_GetUserData CameraImage_GetUserData; + +EXTERN _CameraImage_SetUserData CameraImage_SetUserData; + +EXTERN _CameraImage_IsEmpty CameraImage_IsEmpty; + +EXTERN _CameraImage_Draw CameraImage_Draw; + +EXTERN _CameraImage_BitBlt CameraImage_BitBlt; + +EXTERN _CameraImage_SaveAsBmp CameraImage_SaveAsBmp; + +EXTERN _CameraImage_SaveAsJpeg CameraImage_SaveAsJpeg; + +EXTERN _CameraImage_SaveAsPng CameraImage_SaveAsPng; + +EXTERN _CameraImage_SaveAsRaw CameraImage_SaveAsRaw; + + +CameraSdkStatus LoadSdkApi(); + +CameraSdkStatus UnloadCameraSdk(); + +#ifdef API_LOAD_MAIN +#undef API_LOAD_MAIN + + +//SDK汾ƥ䣬ܳijЩʧܡ + +#define CHCEK_API_LOAD 0 // 1:API⣬ʧܣʾ 0:(ͨSDK汾ŽжԱ) + +#if CHCEK_API_LOAD +#define CHECK_API(API) if(API == NULL)\ +{\ + MessageBoxA(NULL,#API,gSdkLanguageSel?"ʧ":"Function load failed!",0);\ + return CAMERA_STATUS_FAILED;\ +} +#else +#define CHECK_API(API) +#endif + +HMODULE ghSDK = NULL; + +CameraSdkStatus LoadSdkApi() +{ + char szCompany[64]; + char strPath[MAX_PATH]; + char strDir[MAX_PATH]; + HKEY hkey = NULL; + DWORD dwType = REG_SZ; + DWORD dwSize = MAX_PATH; + BYTE abyValue[MAX_PATH]; + LONG status; + + gSdkLanguageSel = 0; + + if (ERROR_SUCCESS != RegOpenKeyExA(HKEY_LOCAL_MACHINE, "Software\\Industry Camera", 0, KEY_READ, &hkey)) + return CAMERA_STATUS_NOT_INITIALIZED; + dwSize = sizeof(szCompany); + status = RegQueryValueExA(hkey, "Company", NULL, &dwType, (LPBYTE)szCompany, &dwSize); + RegCloseKey(hkey); + hkey = NULL; + if (status != ERROR_SUCCESS) + return CAMERA_STATUS_NOT_INITIALIZED; + +#ifdef _WIN64 + sprintf_s(strPath, sizeof(strPath), "Software\\%s\\Settings_X64", szCompany); +#else + sprintf_s(strPath, sizeof(strPath), "Software\\%s\\Settings", szCompany); +#endif + hkey = NULL; + RegCreateKeyExA(HKEY_LOCAL_MACHINE, strPath, 0, NULL, 0, KEY_READ, NULL, &hkey, NULL); + + do + { + if (NULL != hkey) + { + memset(abyValue, 0x00, MAX_PATH); + dwType = REG_SZ; + dwSize = MAX_PATH; + status = RegQueryValueExA(hkey, "Language", NULL, &dwType, abyValue, &dwSize); + if (ERROR_SUCCESS == status) + { + abyValue[MAX_PATH-1] = '\0'; + if (strcmp((const char *)abyValue,"Chinese") == 0) + { + gSdkLanguageSel = 1; + } + else if (strcmp((const char *)abyValue,"TradChinese") == 0) + { + gSdkLanguageSel = 2; + } + } + + dwType = REG_SZ; + dwSize = MAX_PATH; + status = RegQueryValueExA(hkey, "SdkPath", NULL, &dwType, abyValue, &dwSize); + if (ERROR_SUCCESS == status) + { + abyValue[MAX_PATH-1] = '\0'; + strcpy(strPath,(const char *)abyValue); + break; + } + } + + MessageBoxA(NULL, "Failed to access registry", "Error", 0); + return CAMERA_STATUS_FAILED; + } while(0); + + if (hkey != NULL) + { + RegCloseKey(hkey); + hkey = NULL; + } + +#ifndef _WIN64 + sprintf_s(strDir,sizeof(strDir),"%s%s",strPath,"\\MVCAMSDK.dll"); +#else + sprintf_s(strDir,sizeof(strDir),"%s%s",strPath,"\\MVCAMSDK_X64.dll"); +#endif + ghSDK = ::LoadLibraryA(strDir); + + + if (NULL == ghSDK) + { + if (gSdkLanguageSel == 1) + { + sprintf_s(strPath,sizeof(strPath),"ļ[%s]ʧ ,ȷϸ·ڸļ½аװ!",strDir); + MessageBoxA(NULL, strPath, "", 0); + } + else + { + sprintf_s(strPath,sizeof(strPath),"Failed to load file[%s] ,put the file on the directory or re-install the platform and try again!",strDir); + MessageBoxA(NULL, strPath, "Error", 0); + } + return CAMERA_STATUS_FAILED; + } + +#define GET_MVSDK_API(name) \ + name = (_##name)GetProcAddress(ghSDK, #name);\ + CHECK_API(name) + + GET_MVSDK_API(CameraSdkInit); + GET_MVSDK_API(CameraSetCallbackFunction); + GET_MVSDK_API(CameraGetInformation); + GET_MVSDK_API(CameraInit); + GET_MVSDK_API(CameraInitEx); + GET_MVSDK_API(CameraInitEx2); + GET_MVSDK_API(CameraUnInit); + GET_MVSDK_API(CameraImageProcess); + GET_MVSDK_API(CameraImageProcessEx); + GET_MVSDK_API(CameraPlay); + GET_MVSDK_API(CameraPause); + GET_MVSDK_API(CameraStop); + GET_MVSDK_API(CameraDisplayRGB24); + GET_MVSDK_API(CameraSetDisplayMode); + GET_MVSDK_API(CameraImageOverlay); + GET_MVSDK_API(CameraDisplayInit); + GET_MVSDK_API(CameraDisplayInitEx); + GET_MVSDK_API(CameraSetDisplaySize); + GET_MVSDK_API(CameraSetDisplayOffset); + GET_MVSDK_API(CameraInitRecord); + GET_MVSDK_API(CameraStopRecord); + GET_MVSDK_API(CameraPushFrame); + GET_MVSDK_API(CameraSpecialControl); + GET_MVSDK_API(CameraSnapToBuffer); + GET_MVSDK_API(CameraGetImageBuffer); + GET_MVSDK_API(CameraGetImageBufferEx); + GET_MVSDK_API(CameraReleaseImageBuffer); + GET_MVSDK_API(CameraCreateSettingPage); + GET_MVSDK_API(CameraSetActiveSettingSubPage); + GET_MVSDK_API(CameraSetSettingPageParent); + GET_MVSDK_API(CameraGetSettingPageHWnd); + GET_MVSDK_API(CameraSetMirror); + GET_MVSDK_API(CameraGetMirror); + GET_MVSDK_API(CameraSetRotate); + GET_MVSDK_API(CameraGetRotate); + GET_MVSDK_API(CameraSetMonochrome); + GET_MVSDK_API(CameraGetMonochrome); + GET_MVSDK_API(CameraSetInverse); + GET_MVSDK_API(CameraGetInverse); + GET_MVSDK_API(CameraCustomizeResolution); + GET_MVSDK_API(CameraGetImageResolution); + GET_MVSDK_API(CameraGetImageResolutionEx); + GET_MVSDK_API(CameraSetImageResolution); + GET_MVSDK_API(CameraSetImageResolutionEx); + GET_MVSDK_API(CameraGetMediaType); + GET_MVSDK_API(CameraSetMediaType); + GET_MVSDK_API(CameraSetAeState); + GET_MVSDK_API(CameraGetAeState); + GET_MVSDK_API(CameraSetAeTarget); + GET_MVSDK_API(CameraGetAeTarget); + GET_MVSDK_API(CameraSetAeExposureRange); + GET_MVSDK_API(CameraGetAeExposureRange); + GET_MVSDK_API(CameraSetAeAnalogGainRange); + GET_MVSDK_API(CameraGetAeAnalogGainRange); + GET_MVSDK_API(CameraSetAeThreshold); + GET_MVSDK_API(CameraGetAeThreshold); + GET_MVSDK_API(CameraIsAeWinVisible); + GET_MVSDK_API(CameraSetExposureTime); + GET_MVSDK_API(CameraGetExposureTime); + GET_MVSDK_API(CameraGetExposureTimeRange); + GET_MVSDK_API(CameraGetExposureLineTime); + GET_MVSDK_API(CameraSetAnalogGain); + GET_MVSDK_API(CameraGetAnalogGain); + GET_MVSDK_API(CameraSetSharpness); + GET_MVSDK_API(CameraGetSharpness); + GET_MVSDK_API(CameraSetOnceWB); + GET_MVSDK_API(CameraSetLutMode); + GET_MVSDK_API(CameraGetLutMode); + GET_MVSDK_API(CameraSelectLutPreset); + GET_MVSDK_API(CameraGetLutPresetSel); + GET_MVSDK_API(CameraSetCustomLut); + GET_MVSDK_API(CameraGetCustomLut); + GET_MVSDK_API(CameraGetCurrentLut); + GET_MVSDK_API(CameraSetWbMode); + GET_MVSDK_API(CameraGetWbMode); + GET_MVSDK_API(CameraSetWbWindow); + GET_MVSDK_API(CameraIsWbWinVisible); + GET_MVSDK_API(CameraSaveImage); + GET_MVSDK_API(CameraSetGain); + GET_MVSDK_API(CameraGetGain); + GET_MVSDK_API(CameraSetGamma); + GET_MVSDK_API(CameraGetGamma); + GET_MVSDK_API(CameraSetSaturation); + GET_MVSDK_API(CameraGetSaturation); + GET_MVSDK_API(CameraSetContrast); + GET_MVSDK_API(CameraGetContrast); + GET_MVSDK_API(CameraSetFrameSpeed); + GET_MVSDK_API(CameraGetFrameSpeed); + GET_MVSDK_API(CameraSetAntiFlick); + GET_MVSDK_API(CameraGetAntiFlick); + GET_MVSDK_API(CameraGetLightFrequency); + GET_MVSDK_API(CameraSetLightFrequency); + GET_MVSDK_API(CameraSetTransPackLen); + GET_MVSDK_API(CameraGetTransPackLen); + GET_MVSDK_API(CameraWriteSN); + GET_MVSDK_API(CameraReadSN); + GET_MVSDK_API(CameraGetPresetClrTemp); + GET_MVSDK_API(CameraSetPresetClrTemp); + GET_MVSDK_API(CameraSaveParameter); + GET_MVSDK_API(CameraLoadParameter); + GET_MVSDK_API(CameraGetCurrentParameterGroup); + GET_MVSDK_API(CameraEnumerateDevice); + GET_MVSDK_API(CameraEnumerateDeviceEx); + GET_MVSDK_API(CameraGetCapability); + GET_MVSDK_API(CameraSoftTrigger); + GET_MVSDK_API(CameraSetTriggerMode); + GET_MVSDK_API(CameraGetTriggerMode); + GET_MVSDK_API(CameraShowSettingPage); + GET_MVSDK_API(CameraGetFrameStatistic); + GET_MVSDK_API(CameraGetResolutionForSnap); + GET_MVSDK_API(CameraSetResolutionForSnap); + GET_MVSDK_API(CameraGetNoiseFilterState); + GET_MVSDK_API(CameraSetParameterMode); + GET_MVSDK_API(CameraGetParameterMode); + GET_MVSDK_API(CameraSetParameterMask); + GET_MVSDK_API(CameraGetTriggerCount); + GET_MVSDK_API(CameraGetCrossLine); + GET_MVSDK_API(CameraSetCrossLine); + GET_MVSDK_API(CameraGetTriggerDelayTime); + GET_MVSDK_API(CameraSetTriggerDelayTime); + GET_MVSDK_API(CameraSetAeWinVisible); + GET_MVSDK_API(CameraSetNoiseFilter); + GET_MVSDK_API(CameraSetTriggerCount); + GET_MVSDK_API(CameraCustomizeReferWin); + GET_MVSDK_API(CameraSetAeWindow); + GET_MVSDK_API(CameraReadParameterFromFile); + GET_MVSDK_API(CameraSetWbWinVisible); + GET_MVSDK_API(CameraRstTimeStamp); + GET_MVSDK_API(CameraGetCapabilityEx); + GET_MVSDK_API(CameraLoadUserData); + GET_MVSDK_API(CameraSaveUserData); + GET_MVSDK_API(CameraIsOpened); + GET_MVSDK_API(CameraSetFriendlyName); + GET_MVSDK_API(CameraGetFriendlyName); + GET_MVSDK_API(CameraSetUserClrTempGain); + GET_MVSDK_API(CameraGetUserClrTempGain); + GET_MVSDK_API(CameraSetUserClrTempMatrix); + GET_MVSDK_API(CameraGetUserClrTempMatrix); + GET_MVSDK_API(CameraSetClrTempMode); + GET_MVSDK_API(CameraGetClrTempMode); + GET_MVSDK_API(CameraSdkGetVersionString); + GET_MVSDK_API(CameraCheckFwUpdate); + GET_MVSDK_API(CameraGetFirmwareVersion); + GET_MVSDK_API(CameraGetFirmwareVision); + GET_MVSDK_API(CameraGetEnumInfo); + GET_MVSDK_API(CameraGetInerfaceVersion); + GET_MVSDK_API(CameraSetIOState); + GET_MVSDK_API(CameraGetIOState); + GET_MVSDK_API(CameraSetInPutIOMode); + GET_MVSDK_API(CameraSetOutPutIOMode); + GET_MVSDK_API(CameraSetOutPutPWM); + CameraSetBayerDecAlgorithm = (_CameraSetBayerDecAlgorithm)GetProcAddress(ghSDK, +#ifdef _WIN64 + "CameraSetBayerDecAlgorithm"); +#else + "_CameraSetBayerDecAlgorithm@12"); +#endif + CHECK_API(CameraSetBayerDecAlgorithm); + GET_MVSDK_API(CameraGetBayerDecAlgorithm); + GET_MVSDK_API(CameraSetBlackLevel); + GET_MVSDK_API(CameraGetBlackLevel); + GET_MVSDK_API(CameraSetWhiteLevel); + GET_MVSDK_API(CameraGetWhiteLevel); + GET_MVSDK_API(CameraSetIspOutFormat); + GET_MVSDK_API(CameraGetIspOutFormat); + GET_MVSDK_API(CameraSetStrobeMode); + GET_MVSDK_API(CameraGetStrobeMode); + GET_MVSDK_API(CameraSetStrobeDelayTime); + GET_MVSDK_API(CameraGetStrobeDelayTime); + GET_MVSDK_API(CameraSetStrobePulseWidth); + GET_MVSDK_API(CameraGetStrobePulseWidth); + GET_MVSDK_API(CameraSetStrobePolarity); + GET_MVSDK_API(CameraGetStrobePolarity); + GET_MVSDK_API(CameraSetExtTrigSignalType); + GET_MVSDK_API(CameraGetExtTrigSignalType); + GET_MVSDK_API(CameraSetExtTrigShutterType); + GET_MVSDK_API(CameraGetExtTrigShutterType); + GET_MVSDK_API(CameraSetExtTrigDelayTime); + GET_MVSDK_API(CameraGetExtTrigDelayTime); + GET_MVSDK_API(CameraSetExtTrigJitterTime); + GET_MVSDK_API(CameraGetExtTrigJitterTime); + GET_MVSDK_API(CameraGetExtTrigCapability); + GET_MVSDK_API(CameraPauseLevelTrigger); + GET_MVSDK_API(CameraGetErrorString); + GET_MVSDK_API(CameraGetCapabilityEx2); + GET_MVSDK_API(CameraGetImageBufferEx2); + GET_MVSDK_API(CameraGetImageBufferEx3); + GET_MVSDK_API(CameraReConnect); + GET_MVSDK_API(CameraConnectTest); + GET_MVSDK_API(CameraSetLedEnable); + GET_MVSDK_API(CameraGetLedEnable); + GET_MVSDK_API(CameraSetLedOnOff); + GET_MVSDK_API(CameraGetLedOnOff); + GET_MVSDK_API(CameraSetLedDuration); + GET_MVSDK_API(CameraGetLedDuration); + GET_MVSDK_API(CameraSetLedBrightness); + GET_MVSDK_API(CameraGetLedBrightness); + GET_MVSDK_API(CameraEnableTransferRoi); + GET_MVSDK_API(CameraSetTransferRoi); + GET_MVSDK_API(CameraGetTransferRoi); + GET_MVSDK_API(CameraAlignMalloc); + GET_MVSDK_API(CameraAlignFree); + GET_MVSDK_API(CameraSetAutoConnect); + GET_MVSDK_API(CameraGetAutoConnect); + GET_MVSDK_API(CameraGetReConnectCounts); + GET_MVSDK_API(CameraSetSingleGrabMode); + GET_MVSDK_API(CameraGetSingleGrabMode); + GET_MVSDK_API(CameraRestartGrab); + GET_MVSDK_API(CameraDrawText); + GET_MVSDK_API(CameraGigeGetIp); + GET_MVSDK_API(CameraGigeSetIp); + GET_MVSDK_API(CameraGigeGetMac); + GET_MVSDK_API(CameraEnableFastResponse); + GET_MVSDK_API(CameraSetCorrectDeadPixel); + GET_MVSDK_API(CameraGetCorrectDeadPixel); + GET_MVSDK_API(CameraFlatFieldingCorrectSetEnable); + GET_MVSDK_API(CameraFlatFieldingCorrectGetEnable); + GET_MVSDK_API(CameraFlatFieldingCorrectSetParameter); + GET_MVSDK_API(CameraFlatFieldingCorrectSaveParameterToFile); + GET_MVSDK_API(CameraFlatFieldingCorrectLoadParameterFromFile); + GET_MVSDK_API(CameraCommonCall); + GET_MVSDK_API(CameraSetDenoise3DParams); + GET_MVSDK_API(CameraGetDenoise3DParams); + GET_MVSDK_API(CameraManualDenoise3D); + GET_MVSDK_API(CameraCustomizeDeadPixels); + GET_MVSDK_API(CameraReadDeadPixels); + GET_MVSDK_API(CameraAddDeadPixels); + GET_MVSDK_API(CameraRemoveDeadPixels); + GET_MVSDK_API(CameraRemoveAllDeadPixels); + GET_MVSDK_API(CameraSaveDeadPixels); + GET_MVSDK_API(CameraSaveDeadPixelsToFile); + GET_MVSDK_API(CameraLoadDeadPixelsFromFile); + GET_MVSDK_API(CameraGetImageBufferPriority); + GET_MVSDK_API(CameraGetImageBufferPriorityEx); + GET_MVSDK_API(CameraGetImageBufferPriorityEx2); + GET_MVSDK_API(CameraGetImageBufferPriorityEx3); + GET_MVSDK_API(CameraClearBuffer); + GET_MVSDK_API(CameraSoftTriggerEx); + GET_MVSDK_API(CameraSetHDR); + GET_MVSDK_API(CameraGetHDR); + GET_MVSDK_API(CameraGetFrameID); + GET_MVSDK_API(CameraGetFrameTimeStamp); + GET_MVSDK_API(CameraSetHDRGainMode); + GET_MVSDK_API(CameraGetHDRGainMode); + GET_MVSDK_API(CameraCreateDIBitmap); + GET_MVSDK_API(CameraDrawFrameBuffer); + GET_MVSDK_API(CameraFlipFrameBuffer); + GET_MVSDK_API(CameraConvertFrameBufferFormat); + GET_MVSDK_API(CameraSetConnectionStatusCallback); + GET_MVSDK_API(CameraSetLightingControllerMode); + GET_MVSDK_API(CameraSetLightingControllerState); + GET_MVSDK_API(CameraGetEyeCount); + GET_MVSDK_API(CameraMultiEyeImageProcess); + + GET_MVSDK_API(CameraGrabber_CreateFromDevicePage); + GET_MVSDK_API(CameraGrabber_CreateByIndex); + GET_MVSDK_API(CameraGrabber_CreateByName); + GET_MVSDK_API(CameraGrabber_Create); + GET_MVSDK_API(CameraGrabber_Destroy); + GET_MVSDK_API(CameraGrabber_SetHWnd); + GET_MVSDK_API(CameraGrabber_SetPriority); + GET_MVSDK_API(CameraGrabber_StartLive); + GET_MVSDK_API(CameraGrabber_StopLive); + GET_MVSDK_API(CameraGrabber_SaveImage); + GET_MVSDK_API(CameraGrabber_SaveImageAsync); + GET_MVSDK_API(CameraGrabber_SaveImageAsyncEx); + GET_MVSDK_API(CameraGrabber_SetSaveImageCompleteCallback); + GET_MVSDK_API(CameraGrabber_SetFrameListener); + GET_MVSDK_API(CameraGrabber_SetRawCallback); + GET_MVSDK_API(CameraGrabber_SetRGBCallback); + GET_MVSDK_API(CameraGrabber_GetCameraHandle); + GET_MVSDK_API(CameraGrabber_GetStat); + GET_MVSDK_API(CameraGrabber_GetCameraDevInfo); + + GET_MVSDK_API(CameraImage_Create); + GET_MVSDK_API(CameraImage_Destroy); + GET_MVSDK_API(CameraImage_GetData); + GET_MVSDK_API(CameraImage_GetUserData); + GET_MVSDK_API(CameraImage_SetUserData); + GET_MVSDK_API(CameraImage_IsEmpty); + GET_MVSDK_API(CameraImage_Draw); + GET_MVSDK_API(CameraImage_BitBlt); + GET_MVSDK_API(CameraImage_SaveAsBmp); + GET_MVSDK_API(CameraImage_SaveAsJpeg); + GET_MVSDK_API(CameraImage_SaveAsPng); + GET_MVSDK_API(CameraImage_SaveAsRaw); + +#undef GET_MVSDK_API + + return CAMERA_STATUS_SUCCESS; +} + +CameraSdkStatus UnloadCameraSdk() +{ + if (ghSDK) + { + FreeLibrary(ghSDK); + } + return CAMERA_STATUS_SUCCESS; +} +#endif + +#endif diff --git a/others/include/camera/CameraDefine.H b/others/include/camera/CameraDefine.H new file mode 100644 index 0000000..9773ded --- /dev/null +++ b/others/include/camera/CameraDefine.H @@ -0,0 +1,961 @@ +#pragma once +#ifndef _CAMERA_DEFINE_H_ +#define _CAMERA_DEFINE_H_ + +#include "CameraStatus.h" + +#define MAX_CROSS_LINE 9 + +/// @ingroup MV_TYPEDEF +/// \~chinese ľͶ +/// \~english Camera handle type definition +typedef int CameraHandle; + + + +/// @ingroup MV_ENUM_TYPE +/// \~chinese ͼ任ķʽ +/// \~english Image lookup table transformation +typedef enum +{ + LUTMODE_PARAM_GEN=0, ///< \~chinese ͨڲ̬LUT \~english Dynamically generate LUT tables by adjusting parameters. + LUTMODE_PRESET=1, ///< \~chinese ʹԤLUT \~english Use a preset LUT table + LUTMODE_USER_DEF=2 ///< \~chinese ʹûԶLUT \~english Use a user-defined LUT table +}emSdkLutMode; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese Ƶ +/// \~english Camera video flow control +typedef enum +{ + /// \~chinese Ԥͼʾڴģʽȴ֡ĵ + /// \~english Normal preview, the captured image is displayed. (If the camera is in trigger mode, it will wait for the arrival of the trigger frame) + RUNMODE_PLAY=0, + RUNMODE_PAUSE=1, ///< \~chinese ͣͣͼͬʱҲȥͼ \~english Pause, will pause the camera's image output, and will not capture the image. + RUNMODE_STOP=2 ///< \~chinese ֹͣʼʹֹͣģʽ \~english Stop the camera. Camera is in stop mode after deinitialization. +}emSdkRunMode; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese SDKڲʾӿڵʾʽ +/// \~english How to display the internal display interface of the SDK +typedef enum +{ + DISPLAYMODE_SCALE=0, ///< \~chinese ʾģʽŵʾؼijߴ \~english Zoom the display mode, zoom to the size of the display control + DISPLAYMODE_REAL=1, ///< \~chinese 1:1ʾģʽͼߴʾؼijߴʱֻʾֲ \~english 1:1 display mode, when the image size is larger than the size of the display control, only the local display + DISPLAYMODE_2X=2, ///< \~chinese Ŵ2X \~english Zoom in 2X + DISPLAYMODE_4X=3, ///< \~chinese Ŵ4X \~english Zoom in 4X + DISPLAYMODE_8X=4, ///< \~chinese Ŵ8X \~english Zoom in 8X + DISPLAYMODE_16X=5 ///< \~chinese Ŵ16X \~english Zoom in 16X +}emSdkDisplayMode; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese ¼״̬ +/// \~english Recording status +typedef enum +{ + RECORD_STOP=0, ///< \~chinese ֹͣ \~english Stop + RECORD_START=1, ///< \~chinese ¼ \~english Start + RECORD_PAUSE=2 ///< \~chinese ͣ \~english Pause +}emSdkRecordMode; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese ͼľ +/// \~english Image mirroring operation +typedef enum +{ + MIRROR_DIRECTION_HORIZONTAL=0, ///< \~chinese ˮƽ \~english Horizontal mirroring + MIRROR_DIRECTION_VERTICAL=1 ///< \~chinese ֱ \~english Vertical mirroring +}emSdkMirrorDirection; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese ͼת +/// \~english Rotation of the image +typedef enum +{ + ROTATE_DIRECTION_0=0, ///< \~chinese ת \~english Do not rotate + ROTATE_DIRECTION_90=1, ///< \~chinese ʱ90 \~english Counterclockwise 90 degrees + ROTATE_DIRECTION_180=2, ///< \~chinese ʱ180 \~english Counterclockwise 180 degrees + ROTATE_DIRECTION_270=3, ///< \~chinese ʱ270 \~english Counterclockwise 270 degrees +}emSdkRotateDirection; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese Ƶ֡ +/// \~english Camera video frame rate +typedef enum +{ + FRAME_SPEED_LOW=0, ///< \~chinese ģʽ \~english Low Speed + FRAME_SPEED_NORMAL=1, ///< \~chinese ͨģʽ \~english Normal Speed + FRAME_SPEED_HIGH=2, ///< \~chinese ģʽ(ҪϸߵĴ,豸ʱ֡ʵȶӰ) \~english High Speed + FRAME_SPEED_SUPER=3 ///< \~chinese ģʽ(ҪϸߵĴ,豸ʱ֡ʵȶӰ) \~english Super Speed +}emSdkFrameSpeed; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese ļĸʽ +/// \~english Save file format type +typedef enum +{ + FILE_JPG = 1, ///< \~chinese JPG \~english JPG + FILE_BMP = 2, ///< \~chinese BMP 24bit \~english BMP 24bit + FILE_RAW = 4, ///< \~chinese RAW \~english RAW + FILE_PNG = 8, ///< \~chinese PNG 24bit \~english PNG 24bit + FILE_BMP_8BIT = 16, ///< \~chinese BMP 8bit \~english BMP 8bit + FILE_PNG_8BIT = 32, ///< \~chinese PNG 8bit \~english PNG 8bit + FILE_RAW_16BIT = 64 ///< \~chinese RAW 16bit \~english RAW 16bit +}emSdkFileType; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese еͼ񴫸Ĺģʽ +/// \~english Image Sensor Operation Mode in Camera +typedef enum +{ + /// \~chinese ɼģʽ + /// \~english Continuous acquisition mode + CONTINUATION=0, + + /// \~chinese ģʽָ󣬴ʼɼָ֡ͼ񣬲ɼɺֹͣ + /// \~english Software trigger mode. After the software sends the instruction, the sensor starts to capture the image of the specified frame number. After the acquisition is completed, the output is stopped. + SOFT_TRIGGER=1, + + /// \~chinese Ӳģʽյⲿźţʼɼָ֡ͼ񣬲ɼɺֹͣ + /// \~english In the hardware trigger mode, when receiving an external signal, the sensor starts to capture the image of the specified frame number. After the acquisition is completed, the output is stopped. + EXTERNAL_TRIGGER=2 +} emSdkSnapMode; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese ԶعʱƵƵ +/// \~english Anti-strobe frequency at auto exposure +typedef enum +{ + /// \~chinese 50HZ,һĵƹⶼ50HZ + /// \~english 50HZ, the general lighting is 50HZ + LIGHT_FREQUENCY_50HZ=0, + + /// \~chinese 60HZ,Ҫָʾ + /// \~english 60HZ, mainly refers to the monitor + LIGHT_FREQUENCY_60HZ=1 +}emSdkLightFrequency; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese òΪA,B,C,D 4б档 +/// \~english The camera configuration parameters are divided into groups A, B, C, and D for preservation. +typedef enum +{ + PARAMETER_TEAM_DEFAULT = 0xff, ///< \~chinese Ĭϲ \~english Default parameters + PARAMETER_TEAM_A = 0, ///< \~chinese A \~english parametersA + PARAMETER_TEAM_B = 1, ///< \~chinese B \~english parametersB + PARAMETER_TEAM_C = 2, ///< \~chinese C \~english parametersC + PARAMETER_TEAM_D = 3 ///< \~chinese D \~english parametersD +}emSdkParameterTeam; + + +/// @ingroup MV_ENUM_TYPE +/// \~chinese +/// \brief ģʽ +/// \note ԸԼʹûʹϼַʽز磬 +/// \note MV-U300Ϊϣ̨ͺŵ ϶4ô +/// \note ʹPARAM_MODE_BY_MODELʽ;ϣijһ̨ij̨MV-U300 +/// \note ʹԼļMV-U300ҪʹͬIJļôʹ +/// \note PARAM_MODE_BY_NAMEʽ;ϣÿ̨MV-U300ʹòͬIJļô +/// \note ʹPARAM_MODE_BY_SNʽ +/// \note ļڰװĿ¼ \\Camera\\Configs Ŀ¼£configΪ׺ļ +/// \~english +/// \brief Camera parameter loading mode +/// \note You can use the above several ways to load parameters according to your own environment. For example, with +/// \note MV-U300 as an example, you want multiple cameras of this model to share 4 sets of parameters on your computer. +/// \note Use the PARAM_MODE_BY_MODEL method; if you want one or more of the MV-U300s +/// \note Use your own parameter file and the rest of the MV-U300 use the same parameter file again, then use +/// \note PARAM_MODE_BY_NAME way; if you want each MV-U300 to use a different parameter file, then +/// \note Use the PARAM_MODE_BY_SN method. +/// \note The parameter file exists in the \\Camera\\Configs directory of the installation directory, with a config extension file. +typedef enum +{ + /// \~chinese ͺļмزMV-U300 + /// \note ͬͺŵABCDļ޸һ̨IJļӰ쵽ͬͺŵء + /// \~english Load parameters from a file based on the camera model name, such as the MV-U300 + /// \note All ABCD four-group parameter files are shared by all cameras of the same model. Modifying a camera's parameter file will affect the entire camera model parameter loading. + PARAM_MODE_BY_MODEL=0, + + /// \~chinese 豸dz(tSdkCameraDevInfo.acFriendlyName)ļмزMV-U300,dzƿԶ + /// \note 豸ͬABCDļ + /// \note Ĭ£ֻijͺһ̨ʱ + /// \note 豸һģϣijһ̨ܹ + /// \note ͬIJļͨ޸豸ķʽ + /// \note ָIJļ + /// \~english Load parameters from a file based on device nickname (tSdkCameraDevInfo.acFriendlyName), such as MV-U300, which can be customized + /// \note All cameras with the same device name share the four ABCD parameter files. + /// \note By default, when only one model of a camera is connected to the computer, + /// \note The device name is the same, and you want a camera to load + /// \note different parameter files, you can modify the device name + /// \note to have it load the specified parameter file. + PARAM_MODE_BY_NAME=1, + + /// \~chinese 豸ΨһкŴļмزкڳʱѾд豸ÿ̨ӵвͬкš + /// \note ԼΨһкABCDļ + /// \note кڳʱѾ̻ڣÿ̨к + /// \note ַͬͨʽÿ̨IJļǶġ + /// \~english The parameters are loaded from the file according to the unique serial number of the device. The serial number is already written to the device at the factory and each camera has a different serial number. + /// \note The camera loads ABCD four sets of parameter files according to their unique serial number. + /// \note The serial number has been fixed in the camera at the factory, the serial number of each camera + /// \note is not the same. In this way, the parameter files for each camera are independent. + PARAM_MODE_BY_SN=2, + + /// \~chinese 豸Ĺ̬洢мزеͺŶִ֧жд飬tSdkCameraCapbility.bParamInDevice + /// \~english Load parameters from the device's solid-state memory. Not all models support reading and writing parameters from the camera, as determined by tSdkCameraCapbility.bParamInDevice + PARAM_MODE_IN_DEVICE=3 +}emSdkParameterMode; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese SDKɵҳֵ +/// \~english SDK generated camera configuration page mask values +typedef enum +{ + PROP_SHEET_INDEX_EXPOSURE=0, ///< \~chinese ع \~english Exposure Settings + PROP_SHEET_INDEX_ISP_COLOR=1, ///< \~chinese ɫ \~english Color Matrix Settings + PROP_SHEET_INDEX_ISP_LUT=2, ///< \~chinese LUT \~english LUT setting + PROP_SHEET_INDEX_ISP_SHAPE=3, ///< \~chinese 任 \~english transform settings + PROP_SHEET_INDEX_VIDEO_FORMAT=4, ///< \~chinese ʽ \~english Formatting + PROP_SHEET_INDEX_RESOLUTION=5, ///< \~chinese ֱ \~english resolution setting + PROP_SHEET_INDEX_IO_CTRL=6, ///< \~chinese IO \~english IO control + PROP_SHEET_INDEX_TRIGGER_SET=7, ///< \~chinese ģʽ \~english trigger setting + PROP_SHEET_INDEX_OVERLAY=8, ///< \~chinese ʮ \~english Crosshair + PROP_SHEET_INDEX_DEVICE_INFO=9, ///< \~chinese 豸Ϣ \~english Device Information + PROP_SHEET_INDEX_WDR=10 ///< \~chinese ̬ \~english Wide Dynamic +}emSdkPropSheetMask; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese SDKɵҳĻصϢ +/// \~english SDK callback camera configuration page callback message type +typedef enum +{ + SHEET_MSG_LOAD_PARAM_DEFAULT=0, ///< \~chinese ָĬϺ󣬴Ϣ \~english After the parameter is restored to the default, the message is triggered + SHEET_MSG_LOAD_PARAM_GROUP=1, ///< \~chinese ָ飬Ϣ \~english Load the specified parameter group and trigger the message + SHEET_MSG_LOAD_PARAM_FROMFILE=2, ///< \~chinese ָļز󣬴Ϣ \~english Fires the message after loading parameters from the specified file + SHEET_MSG_SAVE_PARAM_GROUP=3 ///< \~chinese ǰ鱻ʱϢ \~english Trigger this message when the current parameter group is saved +}emSdkPropSheetMsg; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese ӻѡοڵ +/// \~english Visualize the type of reference window +typedef enum +{ + REF_WIN_AUTO_EXPOSURE=0, ///< \~chinese Զعⴰ \~english Automatic exposure window + REF_WIN_WHITE_BALANCE=1, ///< \~chinese ƽⴰ \~english White balance window +}emSdkRefWinType; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese ӻѡοڵ +/// \~english Visualize the type of reference window +typedef enum +{ + RES_MODE_PREVIEW=0, ///< \~chinese Ԥ \~english Preview + RES_MODE_SNAPSHOT=1, ///< \~chinese ץ \~english Snapshot +}emSdkResolutionMode; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese ƽʱɫģʽ +/// \~english White balance color temperature mode +typedef enum +{ + CT_MODE_AUTO=0, ///< \~chinese Զʶɫ \~english Automatically recognize color temperature + CT_MODE_PRESET=1, ///< \~chinese ʹָԤɫ \~english Use the specified preset color temperature + CT_MODE_USER_DEF=2 ///< \~chinese Զɫ(;) \~english Custom color temperature (gain and matrix) +}emSdkClrTmpMode; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese LUTɫͨ +/// \~english LUT color channel +typedef enum +{ + LUT_CHANNEL_ALL=0, ///< \~chinese R,B,Gͨͬʱ \~english R, B, G simultaneous adjustment of three channels + LUT_CHANNEL_RED=1, ///< \~chinese ɫͨ \~english Red channel + LUT_CHANNEL_GREEN=2, ///< \~chinese ɫͨ \~english Green channel + LUT_CHANNEL_BLUE=3, ///< \~chinese ɫͨ \~english Blue channel +}emSdkLutChannel; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese ISPԪ +/// \~english ISP processing unit +typedef enum +{ + ISP_PROCESSSOR_PC=0, ///< \~chinese ʹPCISPģ \~english Use software ISP module of PC + ISP_PROCESSSOR_DEVICE=1 ///< \~chinese ʹԴӲISPģ \~english Use the camera's own hardware ISP module +}emSdkIspProcessor; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese źſƷʽ +/// \~english Strobe signal control method +typedef enum +{ + STROBE_SYNC_WITH_TRIG_AUTO=0, ///< \~chinese ʹźͬعʱԶSTROBEźšʱЧԿ(@link #CameraSetStrobePolarity @endlink) \~english Synchronized with the trigger signal, the STROBE signal is automatically generated when the camera performs exposure. At this point, the effective polarity can be set (@link #CameraSetStrobePolarity @endlink). + STROBE_SYNC_WITH_TRIG_MANUAL=1, ///< \~chinese ʹźͬSTROBEʱָʱ(@link #CameraSetStrobeDelayTime @endlink)ٳָʱ(@link #CameraSetStrobePulseWidth @endlink)ЧԿ(@link #CameraSetStrobePolarity @endlink) \~english Synchronized with the trigger signal. After the trigger, STROBE is delayed by the specified time (@link #CameraSetStrobeDelayTime @endlink) and continues for the specified time (@link #CameraSetStrobePulseWidth @endlink). The effective polarity can be set (@link #CameraSetStrobePolarity @endlink). + STROBE_ALWAYS_HIGH=2, ///< \~chinese ʼΪߣSTROBEźŵ \~english Always high, ignoring other settings of the STROBE signal + STROBE_ALWAYS_LOW=3 ///< \~chinese ʼΪͣSTROBEźŵ \~english Always low, ignoring other settings of the STROBE signal +}emStrobeControl; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese Ӳⴥź +/// \~english Signal types triggered by hardware +typedef enum +{ + EXT_TRIG_LEADING_EDGE=0, ///< \~chinese شĬΪ÷ʽ \~english Rising edge trigger, default is this method + EXT_TRIG_TRAILING_EDGE=1, ///< \~chinese ½ش \~english Falling edge trigger + EXT_TRIG_HIGH_LEVEL=2, ///< \~chinese ߵƽ,ƽȾعʱ䣬ͺŵֵ֧ƽʽ \~english The high level triggers, the level width determines the exposure time, only some models of cameras support level triggering. + EXT_TRIG_LOW_LEVEL=3, ///< \~chinese ͵ƽ \~english Low level trigger + EXT_TRIG_DOUBLE_EDGE=4, ///< \~chinese ˫ش \~english Bilateral trigger +}emExtTrigSignal; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese ӲⴥʱĿŷʽ +/// \~english Shutter mode when triggered by hardware +typedef enum +{ + EXT_TRIG_EXP_STANDARD=0, ///< \~chinese ׼ʽĬΪ÷ʽ \~english Standard mode, the default is this mode. + EXT_TRIG_EXP_GRR=1, ///< \~chinese ȫָλʽֹŵCMOSͺŵָ֧÷ʽⲿеţԴﵽȫֿŵЧʺĸ˶ \~english Global reset mode, part of the rolling shutter CMOS model camera supports this method, with the external mechanical shutter, you can achieve the effect of a global shutter, suitable for shooting high-speed objects +}emExtTrigShutterMode; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese 㷨 +/// \~english Sharpness assessment algorithm +typedef enum +{ + EVALUATE_DEFINITION_DEVIATION=0, ///< \~chinese  \~english Variance method + EVALUATE_DEFINITION_SMD=1, ///< \~chinese ػҶȷ \~english Adjacent Pixel Gray Difference Method + EVALUATE_DEFINITION_GRADIENT=2, ///< \~chinese ݶͳ \~english Gradient statistics + EVALUATE_DEFINITION_SOBEL=3, ///< \~chinese Sobel \~english Sobel + EVALUATE_DEFINITION_ROBERT=4, ///< \~chinese Robert \~english Robert + EVALUATE_DEFINITION_LAPLACE=5, ///< \~chinese Laplace \~english Laplace + + EVALUATE_DEFINITION_ALG_MAX=6, ///< \~chinese 㷨 \~english The number of algorithms +}emEvaluateDefinitionAlgorith; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese ־ +/// \~english Text output flag +typedef enum +{ + CAMERA_DT_VCENTER = 0x1, ///< \~chinese ֱ \~english Vertically centered + CAMERA_DT_BOTTOM = 0x2, ///< \~chinese ײ \~english Bottom alignment + CAMERA_DT_HCENTER = 0x4, ///< \~chinese ˮƽ \~english Horizontally centered + CAMERA_DT_RIGHT = 0x8, ///< \~chinese Ҷ \~english Right alignment + CAMERA_DT_SINGLELINE = 0x10, ///< \~chinese ʾ \~english Single-line display + CAMERA_DT_ALPHA_BLEND = 0x20, ///< \~chinese Alpha \~english Alpha blend + CAMERA_DT_ANTI_ALIASING = 0x40, ///< \~chinese \~english Anti-aliasing +}emCameraDrawTextFlags; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese GPIOģʽ +/// \~english GPIO Mode +typedef enum +{ + IOMODE_TRIG_INPUT=0, ///< \~chinese \~english Trigger input + IOMODE_STROBE_OUTPUT=1, ///< \~chinese \~english Strobe output + IOMODE_GP_INPUT=2, ///< \~chinese ͨ \~english Universal input + IOMODE_GP_OUTPUT=3, ///< \~chinese ͨ \~english Universal output + IOMODE_PWM_OUTPUT=4, ///< \~chinese PWM \~english PWM output +}emCameraGPIOMode; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese ȡͼȼ +/// \~english Get Image priority +typedef enum +{ + CAMERA_GET_IMAGE_PRIORITY_OLDEST=0, ///< \~chinese ȡɵһ֡ \~english Get the oldest frame in the cache + CAMERA_GET_IMAGE_PRIORITY_NEWEST=1, ///< \~chinese ȡµһ֡ȴ֡ɵĽȫ \~english Get the latest frame in the cache (older than this frame will be discarded) + + /// \~chinese е֡˿ع佫ᱻϣȴһ֡ + /// \note ijЩͺŵִ֧˹ܣڲִ֧˹ܵ־൱@link #CAMERA_GET_IMAGE_PRIORITY_OLDEST @endlink + /// \~english All frames in the cache are discarded, and if the camera is now being exposed or transmitted it will be immediately interrupted, waiting to receive the next frame + /// \note Some models do not support this feature. For cameras that do not support this feature this flag is equivalent to @link #CAMERA_GET_IMAGE_PRIORITY_OLDEST @endlink + CAMERA_GET_IMAGE_PRIORITY_NEXT=2, +}emCameraGetImagePriority; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese ܱ־ +/// \~english Soft trigger function flag +typedef enum +{ + CAMERA_ST_CLEAR_BUFFER_BEFORE = 0x1, ///< \~chinese ֮ǰѻ֡ \~english Empty camera-cached frames before soft triggering +}emCameraSoftTriggerExFlags; + +/// \~chinese 豸Ϣ +/// \~english Camera device information +typedef struct +{ + char acProductSeries[32]; ///< \~chinese Ʒϵ \~english Product Series + char acProductName[32]; ///< \~chinese Ʒ \~english product name + + /// \~chinese ƷdzƣûԶdzƣڣֶͬʱʹ,@link #CameraSetFriendlyName @endlinkӿڸıdzƣ豸Ч + /// \~english Product nicknames, users can customize the nickname, saved in the camera, used to distinguish between multiple cameras at the same time, you can use the @link #CameraSetFriendlyName @endlink interface to change the nickname, the device takes effect after restart. + char acFriendlyName[32]; + char acLinkName[32]; ///< \~chinese ں˷ڲʹ \~english Kernel symbolic connection name, internal use + char acDriverVersion[32]; ///< \~chinese 汾 \~english Driver version + char acSensorType[32]; ///< \~chinese sensor \~english Sensor type + char acPortType[32]; ///< \~chinese ӿ \~english Interface Type + char acSn[32]; ///< \~chinese ƷΨһк \~english Product unique serial number + UINT uInstance; ///< \~chinese ͺڸõϵʵţͬͺŶ \~english The example index number of this model camera on this computer, used to distinguish the same model multiple cameras +} tSdkCameraDevInfo; + +/// @ingroup MV_MACRO_TYPE +/// @{ +#define EXT_TRIG_MASK_GRR_SHUTTER 1 ///< \~chinese ֧GRRģʽ \~english Shutter supports GRR mode +#define EXT_TRIG_MASK_LEVEL_MODE 2 ///< \~chinese ֵ֧ƽ \~english Support level trigger +#define EXT_TRIG_MASK_DOUBLE_EDGE 4 ///< \~chinese ֧˫ش \~english Supports bilateral triggering + +//tSdkResolutionRangeṹSKIP BINRESAMPLEģʽֵ +#define MASK_2X2_HD (1<<0) //ӲSKIPBINز 2X2 +#define MASK_3X3_HD (1<<1) +#define MASK_4X4_HD (1<<2) +#define MASK_5X5_HD (1<<3) +#define MASK_6X6_HD (1<<4) +#define MASK_7X7_HD (1<<5) +#define MASK_8X8_HD (1<<6) +#define MASK_9X9_HD (1<<7) +#define MASK_10X10_HD (1<<8) +#define MASK_11X11_HD (1<<9) +#define MASK_12X12_HD (1<<10) +#define MASK_13X13_HD (1<<11) +#define MASK_14X14_HD (1<<12) +#define MASK_15X15_HD (1<<13) +#define MASK_16X16_HD (1<<14) +#define MASK_17X17_HD (1<<15) +#define MASK_2X2_SW (1<<16) //SKIPBINز 2X2 +#define MASK_3X3_SW (1<<17) +#define MASK_4X4_SW (1<<18) +#define MASK_5X5_SW (1<<19) +#define MASK_6X6_SW (1<<20) +#define MASK_7X7_SW (1<<21) +#define MASK_8X8_SW (1<<22) +#define MASK_9X9_SW (1<<23) +#define MASK_10X10_SW (1<<24) +#define MASK_11X11_SW (1<<25) +#define MASK_12X12_SW (1<<26) +#define MASK_13X13_SW (1<<27) +#define MASK_14X14_SW (1<<28) +#define MASK_15X15_SW (1<<29) +#define MASK_16X16_SW (1<<30) +#define MASK_17X17_SW (1<<31) +/// @} + +/// \~chinese ķֱ趨ΧڹUI +/// \~english Camera resolution setting range, can be used for component UI +typedef struct +{ + INT iHeightMax; ///< \~chinese ͼ߶ \~english Maximum image height + INT iHeightMin; ///< \~chinese ͼС߶ \~english Image minimum height + INT iWidthMax; ///< \~chinese ͼ \~english The maximum width of the image + INT iWidthMin; ///< \~chinese ͼС \~english The minimum width of the image + UINT uSkipModeMask; ///< \~chinese SKIPģʽ룬Ϊ0ʾ֧SKIP bit0Ϊ1,ʾ֧SKIP 2x2 ;bit1Ϊ1ʾ֧SKIP 3x3.... \~english The SKIP mode mask, which is 0, indicates that SKIP is not supported. Bit0 is 1 to indicate that SKIP 2x2 is supported; bit1 is 1 to indicate that SKIP 3x3 is supported.... + UINT uBinSumModeMask; ///< \~chinese BIN()ģʽ룬Ϊ0ʾ֧BIN bit0Ϊ1,ʾ֧BIN 2x2 ;bit1Ϊ1ʾ֧BIN 3x3.... \~english The BIN (sum) pattern mask, which is 0, indicates that BIN is not supported. Bit0 is 1, indicating that BIN 2x2 is supported; bit1 is 1, indicating that BIN 3x3 is supported.... + UINT uBinAverageModeMask; ///< \~chinese BIN(ֵ)ģʽ룬Ϊ0ʾ֧BIN bit0Ϊ1,ʾ֧BIN 2x2 ;bit1Ϊ1ʾ֧BIN 3x3.... \~english The BIN (mean value) mode mask, which is 0, indicates that BIN is not supported. Bit0 is 1, indicating that BIN 2x2 is supported; bit1 is 1, indicating that BIN 3x3 is supported.... + UINT uResampleMask; ///< \~chinese Ӳز \~english Hardware resampling mask +} tSdkResolutionRange; + +/// \~chinese ķֱ +/// \~english Camera resolution description +typedef struct +{ + INT iIndex; ///< \~chinese ţ[0,N]ʾԤķֱ(N ΪԤֱʵһ㲻20),OXFF ʾԶֱ(ROI) \~english Index number, [0, N] indicates the preset resolution (N is the maximum number of preset resolutions, generally no more than 20), OXFF indicates custom resolution (ROI) + char acDescription[32]; ///< \~chinese ÷ֱʵϢԤֱʱϢЧԶֱʿɺԸϢ \~english The description of the resolution. This information is valid only when the resolution is preset. Custom resolution ignores this information + UINT uBinSumMode; ///< \~chinese BIN()ģʽ,ΧܳtSdkResolutionRange.uBinSumModeMask \~english The BIN (sum) mode cannot exceed the tSdkResolutionRange.uBinSumModeMask + UINT uBinAverageMode; ///< \~chinese BIN(ֵ)ģʽ,ΧܳtSdkResolutionRange.uBinAverageModeMask \~english BIN (average) mode, the range cannot exceed tSdkResolutionRange.uBinAverageModeMask + UINT uSkipMode; ///< \~chinese ǷSKIPijߴ磬Ϊ0ʾֹSKIPģʽΧܳtSdkResolutionRange.uSkipModeMask \~english Whether the SKIP size is 0 indicates that the SKIP mode is disabled and the range cannot exceed the tSdkResolutionRange.uSkipModeMask + UINT uResampleMask; ///< \~chinese Ӳز \~english Hardware resampling mask + INT iHOffsetFOV; ///< \~chinese ɼӳSensorӳϽǵˮƽƫ \~english The horizontal offset of the acquisition field of view relative to the top left corner of the Sensor's largest field of view + INT iVOffsetFOV; ///< \~chinese ɼӳSensorӳϽǵĴֱƫ \~english The vertical offset of the acquisition field of view relative to the upper left corner of the Sensor's largest field of view + INT iWidthFOV; ///< \~chinese ɼӳĿ \~english The width of the field of view + INT iHeightFOV; ///< \~chinese ɼӳĸ߶ \~english The height of the field of view + INT iWidth; ///< \~chinese ͼĿ \~english The width of the final output image of the camera + INT iHeight; ///< \~chinese ͼĸ߶ \~english The height of the final output image of the camera + INT iWidthZoomHd; ///< \~chinese ӲŵĿ,Ҫд˲ķֱʣ˱Ϊ0. \~english The width of the hardware zoom, resolution that does not require this operation, this variable is set to 0. + INT iHeightZoomHd; ///< \~chinese Ӳŵĸ߶,Ҫд˲ķֱʣ˱Ϊ0. \~english The height of the hardware zoom, resolution that does not require this operation, this variable is set to 0. + INT iWidthZoomSw; ///< \~chinese ŵĿ,Ҫд˲ķֱʣ˱Ϊ0. \~english The width of the software's zoom, which does not require the resolution of this operation, this variable is set to 0. + INT iHeightZoomSw; ///< \~chinese ŵĸ߶,Ҫд˲ķֱʣ˱Ϊ0. \~english The height of the software's zoom, which does not require the resolution of this operation, this variable is set to 0. +} tSdkImageResolution; + +/// \~chinese ƽɫģʽϢ +/// \~english Camera white balance color temperature mode description information +typedef struct +{ + INT iIndex; ///< \~chinese ģʽ \~english Mode index number + char acDescription[32]; ///< \~chinese Ϣ \~english Description +} tSdkColorTemperatureDes; + +/// \~chinese ֡Ϣ +/// \~english Camera frame rate description information +typedef struct +{ + INT iIndex; ///< \~chinese ֡ţһ0Ӧڵģʽ1Ӧͨģʽ2Ӧڸģʽ \~english Frame rate index number, generally 0 corresponds to low speed mode, 1 corresponds to normal mode, 2 corresponds to high speed mode + char acDescription[32]; ///< \~chinese Ϣ \~english Description +} tSdkFrameSpeed; + +/// \~chinese ع⹦ܷΧ +/// \see tSdkCameraCapbility.sExposeDesc +/// \~english Camera exposure function scope definition +/// \see tSdkCameraCapbility.sExposeDesc +typedef struct +{ + UINT uiTargetMin; ///< \~chinese ԶعĿСֵ \~english Auto exposure brightness target minimum + UINT uiTargetMax; ///< \~chinese ԶعĿֵ \~english Auto exposure brightness target maximum + UINT uiAnalogGainMin; ///< \~chinese ģСֵλΪfAnalogGainStepж \~english The minimum value of the analog gain in fAnalog defined in GainStep + UINT uiAnalogGainMax; ///< \~chinese ģֵλΪfAnalogGainStepж \~english The maximum value of the analog gain in fAnalog defined in GainStep + float fAnalogGainStep; ///< \~chinese ģÿ1ӦӵķŴ磬uiAnalogGainMinһΪ16fAnalogGainStepһΪ0.125ôСŴ16*0.125 = 2 \~english Each increase in analog gain corresponds to an increased amplification factor. For example, uiAnalogGainMin is generally 16 and fAnalogGainStep is generally 0.125, so the minimum magnification is 16*0.125 = 2 times + UINT uiExposeTimeMin; ///< \~chinese ֶģʽ£عʱСֵλ:СCameraGetExposureLineTimeԻһжӦʱ(΢),Ӷõ֡عʱ \~english The minimum exposure time in manual mode, unit: line. According to CameraGetExposureLineTime can get a row of corresponding time (microseconds) to get the entire frame exposure time + UINT uiExposeTimeMax; ///< \~chinese ֶģʽ£عʱֵλ: \~english Maximum exposure time in manual mode, unit: line +} tSdkExpose; + +/// \~chinese ģʽ +/// \~english Trigger mode description +typedef struct +{ + INT iIndex; ///< \~chinese ģʽ \~english Mode index number + char acDescription[32]; ///< \~chinese ģʽϢ \~english Description information of this mode +} tSdkTrigger; + +/// \~chinese ְС(ijЩЧ) +/// \~english Transmission packet size description (valid for some web cameras) +typedef struct +{ + INT iIndex; ///< \~chinese ְС \~english Packet size index number + char acDescription[32]; ///< \~chinese ӦϢ \~english Corresponding description information + UINT iPackSize; ///< \~chinese С \~english Packet size +} tSdkPackLength; + +/// \~chinese ԤLUT +/// \~english Preset LUT Table Description +typedef struct +{ + INT iIndex; ///< \~chinese \~english index + char acDescription[32]; ///< \~chinese Ϣ \~english description +} tSdkPresetLut; + +/// \~chinese AE㷨 +/// \~english AE algorithm description +typedef struct +{ + INT iIndex; ///< \~chinese \~english index + char acDescription[32]; ///< \~chinese Ϣ \~english description +} tSdkAeAlgorithm; + +/// \~chinese RAWתRGB㷨 +/// \~english RAW to RGB algorithm description +typedef struct +{ + INT iIndex; ///< \~chinese \~english index + char acDescription[32]; ///< \~chinese Ϣ \~english description +} tSdkBayerDecodeAlgorithm; + +/// \~chinese ֡ͳϢ +/// \~english Frame statistics +typedef struct +{ + INT iTotal; ///< \~chinese ǰɼ֡֡ \~english The current total number of frames collected (including error frames) + INT iCapture; ///< \~chinese ǰɼЧ֡ \~english The number of valid frames currently collected + INT iLost; ///< \~chinese ǰ֡ \~english Current number of dropped frames +} tSdkFrameStatistic; + +/// \~chinese ͼݸʽ +/// \~english Camera output image data format +typedef struct +{ + INT iIndex; ///< \~chinese ʽ \~english Format type number + char acDescription[32]; ///< \~chinese Ϣ \~english description + UINT iMediaType; ///< \~chinese Ӧͼʽ룬CAMERA_MEDIA_TYPE_BAYGR8 \~english Corresponding image format encoding, such as CAMERA_MEDIA_TYPE_BAYGR8. +} tSdkMediaType; + +/// \~chinese ٤趨Χ +/// \~english Gamma setting range +typedef struct +{ + INT iMin; ///< \~chinese Сֵ \~english min + INT iMax; ///< \~chinese ֵ \~english max +} tGammaRange; + +/// \~chinese Աȶȵ趨Χ +/// \~english Contrast setting range +typedef struct +{ + INT iMin; ///< \~chinese Сֵ \~english min + INT iMax; ///< \~chinese ֵ \~english max +} tContrastRange; + +/// \~chinese RGBͨ趨Χ +/// \~english RGB three channel digital gain setting range +typedef struct +{ + INT iRGainMin; ///< \~chinese ɫСֵ \~english Red gain minimum + INT iRGainMax; ///< \~chinese ɫֵ \~english Red gain maximum + INT iGGainMin; ///< \~chinese ɫСֵ \~english Green gain minimum + INT iGGainMax; ///< \~chinese ɫֵ \~english Green gain maximum + INT iBGainMin; ///< \~chinese ɫСֵ \~english Blue gain minimum + INT iBGainMax; ///< \~chinese ɫֵ \~english blue gain maximum +} tRgbGainRange; + +/// \~chinese Ͷ趨ķΧ +/// \~english Saturation setting range +typedef struct +{ + INT iMin; ///< \~chinese Сֵ \~english min + INT iMax; ///< \~chinese ֵ \~english max +} tSaturationRange; + +/// \~chinese 񻯵趨Χ +/// \~english Sharpening setting range +typedef struct +{ + INT iMin; ///< \~chinese Сֵ \~english min + INT iMax; ///< \~chinese ֵ \~english max +} tSharpnessRange; + +/// \~chinese ISPģʹϢ +/// \~english ISP module enable information +typedef struct +{ + BOOL bMonoSensor; ///< \~chinese ʾͺǷΪڰ,ǺڰɫصĹܶ޷ \~english Indicates whether this model is a black-and-white camera. If it is a black-and-white camera, color-related functions cannot be adjusted. + BOOL bWbOnce; ///< \~chinese ʾͺǷֶ֧ƽ⹦ \~english Indicates whether this model camera supports manual white balance function + BOOL bAutoWb; ///< \~chinese ʾͺǷ֧Զƽ⹦ \~english Indicates whether this model camera supports automatic white balance function + BOOL bAutoExposure; ///< \~chinese ʾͺǷ֧Զع⹦ \~english Indicates whether this model camera supports auto exposure function + BOOL bManualExposure; ///< \~chinese ʾͺǷֶ֧ع⹦ \~english Indicates whether this model camera supports manual exposure function + BOOL bAntiFlick; ///< \~chinese ʾͺǷֿ֧Ƶ \~english Indicates whether this model camera supports anti-strobe function + BOOL bDeviceIsp; ///< \~chinese ʾͺǷ֧ӲISP \~english Indicates whether this model camera supports hardware ISP function + BOOL bForceUseDeviceIsp;///< \~chinese bDeviceIspbForceUseDeviceIspͬʱΪTRUEʱʾǿֻӲISPȡ \~english When both bDeviceIsp and bForceUseDeviceIsp are TRUE, this means that only the hardware ISP is forced and cannot be cancelled. + BOOL bZoomHD; ///< \~chinese ӲǷ֧ͼ(ֻС) \~english Whether the camera hardware supports image scaling output (can only be reduced). +} tSdkIspCapacity; + +/// \~chinese ϵ豸ϢЩϢڶ̬UI +/// \note @link #CameraGetCapability @endlinkȡṹ +/// \~english Define integrated device description information that can be used to dynamically build UI +/// \note call @link #CameraGetCapability @endlink to get this structure +typedef struct +{ + + tSdkTrigger *pTriggerDesc; ///< \~chinese ģʽ \~english trigger mode + INT iTriggerDesc; ///< \~chinese ģʽĸpTriggerDescĴС \~english The number of trigger modes, that is, the size of the pTriggerDesc array + + tSdkImageResolution *pImageSizeDesc;///< \~chinese Ԥֱ \~english Preset resolution + INT iImageSizeDesc; ///< \~chinese ԤֱʵĸpImageSizeDescĴС \~english The number of preset resolutions, that is, the size of the pImageSizeDesc array + + tSdkColorTemperatureDes *pClrTempDesc;///< \~chinese Ԥɫ£ڰƽ \~english Preset color temperature for white balance + INT iClrTempDesc; ///< \~chinese Ԥɫ¸ \~english The number of preset color temperatures + + tSdkMediaType *pMediaTypeDesc; ///< \~chinese ͼʽ \~english Camera output image format + INT iMediaTypdeDesc; ///< \~chinese ͼʽpMediaTypeDescĴС \~english The number of types of camera output image formats, that is, the size of the pMediaTypeDesc array. + + tSdkFrameSpeed *pFrameSpeedDesc; ///< \~chinese ɵ֡ͣӦͨ ͳٶ \~english Adjustable frame rate type, normal high speed and super three speed settings on the corresponding interface + INT iFrameSpeedDesc; ///< \~chinese ɵ֡͵ĸpFrameSpeedDescĴС \~english The number of frame rate types that can be adjusted, that is, the size of the pFrameSpeedDesc array. + + tSdkPackLength *pPackLenDesc; ///< \~chinese ȣһ豸 \~english Transmission packet length, generally used for network equipment + INT iPackLenDesc; ///< \~chinese ɹѡĴְȵĸpPackLenDescĴС \~english The number of transmission packetization lengths available for selection, which is the size of the pPackLenDesc array. + + INT iOutputIoCounts; ///< \~chinese ɱIOĸ \~english Number of programmable output IOs + INT iInputIoCounts; ///< \~chinese ɱIOĸ \~english Number of programmable input IOs + + tSdkPresetLut *pPresetLutDesc; ///< \~chinese ԤLUT \~english Camera preset LUT table + INT iPresetLut; ///< \~chinese ԤLUTĸpPresetLutDescĴС \~english The number of LUT tables preset by the camera, that is, the size of the pPresetLutDesc array + + INT iUserDataMaxLen; ///< \~chinese ָʾڱû󳤶ȡΪ0ʾޡ \~english Indicates the maximum length in the camera used to save the user data area. 0 means no. + BOOL bParamInDevice; ///< \~chinese ָʾ豸Ƿִ֧豸жд顣1Ϊ֧֣0֧֡ \~english Indicates whether the device supports reading and writing parameter groups from the device. 1 is supported, 0 is not supported. + + tSdkAeAlgorithm *pAeAlmSwDesc; ///< \~chinese Զع㷨 \~english Software auto exposure algorithm description + int iAeAlmSwDesc; ///< \~chinese Զع㷨 \~english Software automatic exposure algorithm number + + tSdkAeAlgorithm *pAeAlmHdDesc; ///< \~chinese ӲԶع㷨ΪNULLʾ֧ӲԶع \~english Hardware auto exposure algorithm description, NULL means hardware auto exposure is not supported + int iAeAlmHdDesc; ///< \~chinese ӲԶع㷨Ϊ0ʾ֧ӲԶع \~english Number of hardware auto exposure algorithms, 0 means hardware auto exposure is not supported + + tSdkBayerDecodeAlgorithm *pBayerDecAlmSwDesc; ///< \~chinese BayerתΪRGBݵ㷨 \~english Algorithm Description of Software Bayer Conversion to RGB Data + int iBayerDecAlmSwDesc; ///< \~chinese BayerתΪRGBݵ㷨 \~english The number of algorithms that Bayer converts to RGB data + + tSdkBayerDecodeAlgorithm *pBayerDecAlmHdDesc; ///< \~chinese ӲBayerתΪRGBݵ㷨ΪNULLʾ֧ \~english Hardware Bayer converts to RGB data algorithm description, is not supported for NULL representation + int iBayerDecAlmHdDesc; ///< \~chinese ӲBayerתΪRGBݵ㷨Ϊ0ʾ֧ \~english The number of algorithms that hardware Bayer converts to RGB data, 0 means not supported + + /* ͼĵڷΧ,ڶ̬UI*/ + tSdkExpose sExposeDesc; ///< \~chinese عķΧֵ \~english Exposure range value + tSdkResolutionRange sResolutionRange; ///< \~chinese ֱʷΧ \~english Resolution range description + tRgbGainRange sRgbGainRange; ///< \~chinese ͼ淶Χ \~english Image digital gain range description + tSaturationRange sSaturationRange; ///< \~chinese ͶȷΧ \~english Saturation range description + tGammaRange sGammaRange; ///< \~chinese ٤Χ \~english Gamma range description + tContrastRange sContrastRange; ///< \~chinese ԱȶȷΧ \~english Contrast range description + tSharpnessRange sSharpnessRange; ///< \~chinese 񻯷Χ \~english Sharpening range description + tSdkIspCapacity sIspCapacity; ///< \~chinese ISP \~english ISP capability description + + +} tSdkCameraCapbility; + + +/// \~chinese ͼ֡ͷϢ +/// \~english Image frame header information +typedef struct +{ + UINT uiMediaType; ///< \~chinese ͼʽ \~english Image Format + UINT uBytes; ///< \~chinese ͼֽ \~english Total bytes + INT iWidth; ///< \~chinese ͼĿȣͼ󣬸ñܱ̬޸ģָʾͼߴ \~english The width of the image, after calling the image processing function, the variable may be dynamically modified to indicate the image size after processing + INT iHeight; ///< \~chinese ͼĸ߶ȣͼ󣬸ñܱ̬޸ģָʾͼߴ \~english The height of the image, after calling the image processing function, the variable may be dynamically modified to indicate the image size after processing + INT iWidthZoomSw; ///< \~chinese ŵĿ,Ҫüͼ񣬴˱Ϊ0. \~english The width of the software zoom, which does not require software cropping. This variable is set to 0. + INT iHeightZoomSw; ///< \~chinese ŵĸ߶,Ҫüͼ񣬴˱Ϊ0. \~english Software zoom height, no software cropped image is required. This variable is set to 0. + BOOL bIsTrigger; ///< \~chinese ָʾǷΪ֡ \~english is trigger + UINT uiTimeStamp; ///< \~chinese ֡IJɼʱ䣬λ0.1 \~english The frame acquisition time, in units of 0.1 milliseconds + UINT uiExpTime; ///< \~chinese ǰͼعֵλΪ΢us \~english Exposure of the current image in microseconds us + float fAnalogGain; ///< \~chinese ǰͼģ汶 \~english The current image's analog gain multiplier + INT iGamma; ///< \~chinese ֡ͼ٤趨ֵLUTģʽΪ̬ʱЧģʽΪ-1 \~english The gamma setting value of the frame image is valid only when the LUT mode is a dynamic parameter generation, and is -1 in other modes. + INT iContrast; ///< \~chinese ֡ͼĶԱȶ趨ֵLUTģʽΪ̬ʱЧģʽΪ-1 \~english The contrast setting value of the frame image is only valid when the LUT mode is generated by the dynamic parameter, and is -1 in other modes. + INT iSaturation; ///< \~chinese ֡ͼıͶ趨ֵںڰ壬Ϊ0 \~english The saturation value of the frame image, which is meaningless for a black and white camera, is 0 + float fRgain; ///< \~chinese ֡ͼĺɫ汶ںڰ壬Ϊ1 \~english The red digital gain multiple of this frame image processing is meaningless for a black and white camera and is 1 + float fGgain; ///< \~chinese ֡ͼɫ汶ںڰ壬Ϊ1 \~english The green digital gain multiplier for this frame image processing, meaning no significance for black and white cameras, is 1 + float fBgain; ///< \~chinese ֡ͼɫ汶ںڰ壬Ϊ1 \~english The blue digital gain multiplier for this frame image processing, meaning no significance for black and white cameras, is 1 +}tSdkFrameHead; + +/// \~chinese ͼ֡ +/// \~english Image frame description +typedef struct sCameraFrame +{ + tSdkFrameHead head; ///< \~chinese ֡ͷ \~english Frame Head + BYTE * pBuffer; ///< \~chinese \~english Image Data +}tSdkFrame; + +/// @ingroup API_GRAB_CB +/// \~chinese ͼ񲶻Ļص +/// \~english Callback function definition for image capture +typedef void (WINAPI* CAMERA_SNAP_PROC)(CameraHandle hCamera, BYTE *pFrameBuffer, tSdkFrameHead* pFrameHead,PVOID pContext); + +/// @ingroup API_SETTINGS_PAGE +/// \~chinese ҳϢص +/// \~english camera configuration page message callback function definition +typedef void (WINAPI* CAMERA_PAGE_MSG_PROC)(CameraHandle hCamera,UINT MSG,UINT uParam,PVOID pContext); + +/// @ingroup API_RECONNECT +/// \~chinese ״̬ص +/// \param [in] hCamera +/// \param [in] MSG Ϣ0: ӶϿ 1: ӻָ +/// \param [in] uParam Ϣ +/// \param [in] pContext û +/// \return +/// \note USBuParamȡֵ +/// \note δ +/// \note uParamȡֵ +/// \note MSG=0ʱδ +/// \note MSG=1ʱ +/// \note 0ϴεԭͨѶʧ +/// \note 1ϴεԭ +/// \~english Camera connection status callback +/// \param [in] hCamera Camera handle +/// \param [in] MSG message, 0: Camera disconnected 1: Camera connection restored +/// \param [in] uParam Additional Information +/// \param [in] pContext user data +/// \return None +/// \note USB camera uParam value: +/// \note Undefined +/// \note network camera uParam value: +/// \note When MSG=0: Undefined +/// \note When MSG=1: +/// \note 0: The last dropped reason, network communication failed +/// \note 1: The last dropped reason, the camera lost power +typedef void (WINAPI* CAMERA_CONNECTION_STATUS_CALLBACK)(CameraHandle hCamera,UINT MSG,UINT uParam,PVOID pContext); + + +////////////////////////////////////////////////////////////////////////// +// Grabber + +/// \~chinese GrabberͳϢ +/// \~english Grabber statistics +typedef struct +{ + int Width; ///< \~chinese ֡ \~english Frame image width + int Height; ///< \~chinese ֡߶ \~english Frame image height + int Disp; ///< \~chinese ʾ֡ \~english Display frame number + int Capture; ///< \~chinese ɼЧ֡ \~english The number of valid frames collected + int Lost; ///< \~chinese ֡ \~english The number of dropped frames + int Error; ///< \~chinese ֡ \~english The number of error frames + float DispFps; ///< \~chinese ʾ֡ \~english Display frame rate + float CapFps; ///< \~chinese ֡ \~english Capture frame rate +}tSdkGrabberStat; + +/// @ingroup GRABBER_CB +/// \~chinese ͼ񲶻Ļص +/// \~english Callback function definition for image capture +typedef void (__stdcall *pfnCameraGrabberFrameCallback)( + void* Grabber, + BYTE *pFrameBuffer, + tSdkFrameHead* pFrameHead, + void* Context); + +/// @ingroup GRABBER_CB +/// \~chinese ֡ +/// \param [in] Grabber +/// \param [in] Phase ͼ׶ +/// \param [in] pFrameBuffer ֡ +/// \param [in] pFrameHead ֡ͷ +/// \param [in] Context û +/// \return 0:Grabberᶪ֡Դ֡к׶ 1:һ׶δ +/// \note ÿGrabberһ֡ͼʱ3׶εFrameListener +/// \note ׶0: RAWݴpFrameBuffer=Raw +/// \note ׶1: ͼǰpFrameBuffer=RGB +/// \note ׶2: ʾǰpFrameBuffer=RGB +/// \note رģߺ˻صҲᱻãʱPhase=-1pFrameBuffer=NULL,pFrameHead=NULL +/// \~english Frame listening function definition +/// \param [in] Grabber +/// \param [in] Phase image processing phase +/// \param [in] pFrameBuffer frame data +/// \param [in] pFrameHead Frame Header +/// \param [in] Context user data +/// \return 0: Grabber will discard this frame and end all subsequent processing stages for this frame 1: Continue to the next stage of processing +/// \note Whenever Grabber captures a frame of image, it will call FrameListener in turn in 3 stages. +/// \note Phase 0: RAW data processing, pFrameBuffer= Raw data +/// \note Phase 1: Screenshot pre-processing, pFrameBuffer=RGB data +/// \note Phase 2: Display preprocessing, pFrameBuffer=RGB data +/// \note In particular, this callback will be called when the camera is disconnected. At this time, Phase=-1, pFrameBuffer=NULL, and pFrameHead=NULL. +typedef int (__stdcall *pfnCameraGrabberFrameListener)( + void* Grabber, + int Phase, + BYTE *pFrameBuffer, + tSdkFrameHead* pFrameHead, + void* Context); + +/// @ingroup GRABBER_SNAPSHOT +/// \~chinese 첽ץͼĻص +/// \warning ImageҪ @link CameraImage_Destroy @endlink ͷ +/// \~english Asynchronous snapshot callback function definition +/// \warning Image needs to call @link CameraImage_Destroy @endlink to release +typedef void (__stdcall *pfnCameraGrabberSaveImageComplete)( + void* Grabber, + void* Image, // ҪCameraImage_Destroyͷ + CameraSdkStatus Status, + void* Context + ); + + +/// @ingroup MV_MACRO_TYPE +/// @{ +//----------------------------IMAGE FORMAT DEFINE------------------------------------ +//----------------------------ͼʽ------------------------------------------- +#define CAMERA_MEDIA_TYPE_MONO 0x01000000 +#define CAMERA_MEDIA_TYPE_RGB 0x02000000 +#define CAMERA_MEDIA_TYPE_COLOR 0x02000000 +#define CAMERA_MEDIA_TYPE_CUSTOM 0x80000000 +#define CAMERA_MEDIA_TYPE_COLOR_MASK 0xFF000000 +#define CAMERA_MEDIA_TYPE_OCCUPY1BIT 0x00010000 +#define CAMERA_MEDIA_TYPE_OCCUPY2BIT 0x00020000 +#define CAMERA_MEDIA_TYPE_OCCUPY4BIT 0x00040000 +#define CAMERA_MEDIA_TYPE_OCCUPY8BIT 0x00080000 +#define CAMERA_MEDIA_TYPE_OCCUPY10BIT 0x000A0000 +#define CAMERA_MEDIA_TYPE_OCCUPY12BIT 0x000C0000 +#define CAMERA_MEDIA_TYPE_OCCUPY16BIT 0x00100000 +#define CAMERA_MEDIA_TYPE_OCCUPY24BIT 0x00180000 +#define CAMERA_MEDIA_TYPE_OCCUPY32BIT 0x00200000 +#define CAMERA_MEDIA_TYPE_OCCUPY36BIT 0x00240000 +#define CAMERA_MEDIA_TYPE_OCCUPY48BIT 0x00300000 +#define CAMERA_MEDIA_TYPE_OCCUPY64BIT 0x00400000 + +#define CAMERA_MEDIA_TYPE_EFFECTIVE_PIXEL_SIZE_MASK 0x00FF0000 +#define CAMERA_MEDIA_TYPE_EFFECTIVE_PIXEL_SIZE_SHIFT 16 + +#define CAMERA_MEDIA_TYPE_PIXEL_SIZE(type) (((type) & CAMERA_MEDIA_TYPE_EFFECTIVE_PIXEL_SIZE_MASK) >> CAMERA_MEDIA_TYPE_EFFECTIVE_PIXEL_SIZE_SHIFT) + + +#define CAMERA_MEDIA_TYPE_ID_MASK 0x0000FFFF +#define CAMERA_MEDIA_TYPE_COUNT 0x46 + +/*mono*/ +#define CAMERA_MEDIA_TYPE_MONO1P (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY1BIT | 0x0037) +#define CAMERA_MEDIA_TYPE_MONO2P (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY2BIT | 0x0038) +#define CAMERA_MEDIA_TYPE_MONO4P (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY4BIT | 0x0039) +#define CAMERA_MEDIA_TYPE_MONO8 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x0001) +#define CAMERA_MEDIA_TYPE_MONO8S (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x0002) +#define CAMERA_MEDIA_TYPE_MONO10 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0003) +#define CAMERA_MEDIA_TYPE_MONO10_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0004) +#define CAMERA_MEDIA_TYPE_MONO12 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0005) +#define CAMERA_MEDIA_TYPE_MONO12_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0006) +#define CAMERA_MEDIA_TYPE_MONO14 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0025) +#define CAMERA_MEDIA_TYPE_MONO16 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0007) + +/*Bayer */ +#define CAMERA_MEDIA_TYPE_BAYGR8 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x0008) +#define CAMERA_MEDIA_TYPE_BAYRG8 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x0009) +#define CAMERA_MEDIA_TYPE_BAYGB8 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x000A) +#define CAMERA_MEDIA_TYPE_BAYBG8 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x000B) + +#define CAMERA_MEDIA_TYPE_BAYGR10_MIPI (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY10BIT | 0x0026) +#define CAMERA_MEDIA_TYPE_BAYRG10_MIPI (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY10BIT | 0x0027) +#define CAMERA_MEDIA_TYPE_BAYGB10_MIPI (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY10BIT | 0x0028) +#define CAMERA_MEDIA_TYPE_BAYBG10_MIPI (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY10BIT | 0x0029) + + +#define CAMERA_MEDIA_TYPE_BAYGR10 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x000C) +#define CAMERA_MEDIA_TYPE_BAYRG10 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x000D) +#define CAMERA_MEDIA_TYPE_BAYGB10 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x000E) +#define CAMERA_MEDIA_TYPE_BAYBG10 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x000F) + +#define CAMERA_MEDIA_TYPE_BAYGR12 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0010) +#define CAMERA_MEDIA_TYPE_BAYRG12 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0011) +#define CAMERA_MEDIA_TYPE_BAYGB12 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0012) +#define CAMERA_MEDIA_TYPE_BAYBG12 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0013) + + +#define CAMERA_MEDIA_TYPE_BAYGR10_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0026) +#define CAMERA_MEDIA_TYPE_BAYRG10_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0027) +#define CAMERA_MEDIA_TYPE_BAYGB10_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0028) +#define CAMERA_MEDIA_TYPE_BAYBG10_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0029) + +#define CAMERA_MEDIA_TYPE_BAYGR12_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x002A) +#define CAMERA_MEDIA_TYPE_BAYRG12_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x002B) +#define CAMERA_MEDIA_TYPE_BAYGB12_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x002C) +#define CAMERA_MEDIA_TYPE_BAYBG12_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x002D) + +#define CAMERA_MEDIA_TYPE_BAYGR16 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x002E) +#define CAMERA_MEDIA_TYPE_BAYRG16 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x002F) +#define CAMERA_MEDIA_TYPE_BAYGB16 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0030) +#define CAMERA_MEDIA_TYPE_BAYBG16 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0031) + +/*RGB */ +#define CAMERA_MEDIA_TYPE_RGB8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0014) +#define CAMERA_MEDIA_TYPE_BGR8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0015) +#define CAMERA_MEDIA_TYPE_RGBA8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY32BIT | 0x0016) +#define CAMERA_MEDIA_TYPE_BGRA8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY32BIT | 0x0017) +#define CAMERA_MEDIA_TYPE_RGB10 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0018) +#define CAMERA_MEDIA_TYPE_BGR10 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0019) +#define CAMERA_MEDIA_TYPE_RGB12 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x001A) +#define CAMERA_MEDIA_TYPE_BGR12 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x001B) +#define CAMERA_MEDIA_TYPE_RGB16 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0033) +#define CAMERA_MEDIA_TYPE_BGR16 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x004B) +#define CAMERA_MEDIA_TYPE_RGBA16 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY64BIT | 0x0064) +#define CAMERA_MEDIA_TYPE_BGRA16 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY64BIT | 0x0051) +#define CAMERA_MEDIA_TYPE_RGB10V1_PACKED (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY32BIT | 0x001C) +#define CAMERA_MEDIA_TYPE_RGB10P32 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY32BIT | 0x001D) +#define CAMERA_MEDIA_TYPE_RGB12V1_PACKED (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY36BIT | 0X0034) +#define CAMERA_MEDIA_TYPE_RGB565P (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0035) +#define CAMERA_MEDIA_TYPE_BGR565P (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0X0036) + +/*YUV and YCbCr*/ +#define CAMERA_MEDIA_TYPE_YUV411_8_UYYVYY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x001E) +#define CAMERA_MEDIA_TYPE_YUV422_8_UYVY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x001F) +#define CAMERA_MEDIA_TYPE_YUV422_8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0032) +#define CAMERA_MEDIA_TYPE_YUV8_UYV (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0020) +#define CAMERA_MEDIA_TYPE_YCBCR8_CBYCR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x003A) +//CAMERA_MEDIA_TYPE_YCBCR422_8 : YYYYCbCrCbCr +#define CAMERA_MEDIA_TYPE_YCBCR422_8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x003B) +#define CAMERA_MEDIA_TYPE_YCBCR422_8_CBYCRY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0043) +#define CAMERA_MEDIA_TYPE_YCBCR411_8_CBYYCRYY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x003C) +#define CAMERA_MEDIA_TYPE_YCBCR601_8_CBYCR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x003D) +#define CAMERA_MEDIA_TYPE_YCBCR601_422_8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x003E) +#define CAMERA_MEDIA_TYPE_YCBCR601_422_8_CBYCRY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0044) +#define CAMERA_MEDIA_TYPE_YCBCR601_411_8_CBYYCRYY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x003F) +#define CAMERA_MEDIA_TYPE_YCBCR709_8_CBYCR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0040) +#define CAMERA_MEDIA_TYPE_YCBCR709_422_8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0041) +#define CAMERA_MEDIA_TYPE_YCBCR709_422_8_CBYCRY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0045) +#define CAMERA_MEDIA_TYPE_YCBCR709_411_8_CBYYCRYY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0042) + +/*RGB Planar */ +#define CAMERA_MEDIA_TYPE_RGB8_PLANAR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0021) +#define CAMERA_MEDIA_TYPE_RGB10_PLANAR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0022) +#define CAMERA_MEDIA_TYPE_RGB12_PLANAR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0023) +#define CAMERA_MEDIA_TYPE_RGB16_PLANAR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0024) + +/*MindVision 12bit packed bayer*/ +#define CAMERA_MEDIA_TYPE_BAYGR12_PACKED_MV (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0060) +#define CAMERA_MEDIA_TYPE_BAYRG12_PACKED_MV (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0061) +#define CAMERA_MEDIA_TYPE_BAYGB12_PACKED_MV (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0062) +#define CAMERA_MEDIA_TYPE_BAYBG12_PACKED_MV (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0063) + +/*MindVision 12bit packed monochome*/ +#define CAMERA_MEDIA_TYPE_MONO12_PACKED_MV (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0064) +/// @} + +#endif diff --git a/others/include/camera/CameraGrabber.h b/others/include/camera/CameraGrabber.h new file mode 100644 index 0000000..6cac2f4 --- /dev/null +++ b/others/include/camera/CameraGrabber.h @@ -0,0 +1,333 @@ +#ifndef _MV_CAMERA_GRABBER_H_ +#define _MV_CAMERA_GRABBER_H_ + +#include "CameraDefine.h" +#include "CameraStatus.h" + + +/// @ingroup GRABBER_CREATE +/// \~chinese +/// \brief бûѡҪ򿪵 +/// \param [out] Grabber ´IJɼ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ڲʹ @link CameraInit @endlink ˿ʹ @link CameraGrabber_GetCameraHandle @endlink ȡʹSDK API +/// \~english +/// \brief Pop-up camera list allows the user to select the camera to open +/// \param [out] Grabber returns newly created grabber +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note This function uses @link CameraInit @endlink internally to open the camera, so you can use @link CameraGrabber_GetCameraHandle @endlink to get the camera handle and use other SDK APIs to operate the camera. +MVSDK_API CameraSdkStatus __stdcall CameraGrabber_CreateFromDevicePage( + void** Grabber + ); + +/// @ingroup GRABBER_CREATE +/// \~chinese +/// \brief ʹбGrabber +/// \param [out] Grabber ´IJɼ +/// \param [in] Index +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ڲʹ @link CameraInit @endlink ˿ʹ @link CameraGrabber_GetCameraHandle @endlink ȡʹSDK API +/// \~english +/// \brief Creating a Grabber Using a Camera List Index +/// \param [out] Grabber returns newly created grabber +/// \param [in] Index Camera index +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note This function uses @link CameraInit @endlink internally to open the camera, so you can use @link CameraGrabber_GetCameraHandle @endlink to get the camera handle and use other SDK APIs to operate the camera. +MVSDK_API CameraSdkStatus __stdcall CameraGrabber_CreateByIndex( + void** Grabber, + int Index + ); + +/// @ingroup GRABBER_CREATE +/// \~chinese +/// \brief ʹƴGrabber +/// \param [out] Grabber ´IJɼ +/// \param [in] Name ơ@link #tSdkCameraDevInfo.acFriendlyName @endlink +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ڲʹ @link CameraInit @endlink ˿ʹ @link CameraGrabber_GetCameraHandle @endlink ȡʹSDK API +/// \~english +/// \brief Create a Grabber with a Camera Name +/// \param [out] Grabber returns newly created grabber +/// \param [in] Name Camera name.@link #tSdkCameraDevInfo.acFriendlyName @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note This function uses @link CameraInit @endlink internally to open the camera, so you can use @link CameraGrabber_GetCameraHandle @endlink to get the camera handle and use other SDK APIs to operate the camera. +MVSDK_API CameraSdkStatus __stdcall CameraGrabber_CreateByName( + void** Grabber, + char* Name + ); + +/// @ingroup GRABBER_CREATE +/// \~chinese +/// \brief 豸ϢGrabber +/// \param [out] Grabber ´IJɼ +/// \param [in] pDevInfo 豸Ϣ@link #CameraEnumerateDevice @endlink +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note ڲʹ @link CameraInit @endlink ˿ʹ @link CameraGrabber_GetCameraHandle @endlink ȡʹSDK API +/// \~english +/// \brief Create Grabber from device info +/// \param [out] Grabber returns newly created grabber +/// \param [in] pDevInfo device information. @link #CameraEnumerateDevice @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note This function uses @link CameraInit @endlink internally to open the camera, so you can use @link CameraGrabber_GetCameraHandle @endlink to get the camera handle and use other SDK APIs to operate the camera. +MVSDK_API CameraSdkStatus __stdcall CameraGrabber_Create( + void** Grabber, + tSdkCameraDevInfo* pDevInfo + ); + +/// @ingroup GRABBER_DESTROY +/// \~chinese +/// \brief Grabber +/// \param [in] Grabber ɼ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Destroy Grabber +/// \param [in] Grabber +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGrabber_Destroy( + void* Grabber + ); + +/// @ingroup GRABBER_CTRL +/// \~chinese +/// \brief ԤƵʾ +/// \param [in] Grabber ɼ +/// \param [in] hWnd ʾڵĴھ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set the preview video display window +/// \param [in] Grabber +/// \param [in] hWnd window handle of the display window +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGrabber_SetHWnd( + void* Grabber, + HWND hWnd + ); + +/// @ingroup GRABBER_CTRL +/// \~chinese +/// \brief Grabberȡͼʱʹõȼ +/// \param [in] Grabber ɼ +/// \param [in] Priority ȡͼȼ @link #emCameraGetImagePriority @endlink +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Sets the priority used by Grabber when fetching graphs +/// \param [in] Grabber +/// \param [in] Priority GetImageBuffer priority, For details see: @link #emCameraGetImagePriority @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGrabber_SetPriority( + void* Grabber, + UINT Priority + ); + +/// @ingroup GRABBER_CTRL +/// \~chinese +/// \brief ʼɼ +/// \param [in] Grabber ɼ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \note Grabberɼ״̬ɼصץͼȹܲ +/// \~english +/// \brief Start Grabber +/// \param [in] Grabber +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \note Grabber must enter the acquisition state, grab callbacks, snapshot and other functions in order to function properly +MVSDK_API CameraSdkStatus __stdcall CameraGrabber_StartLive( + void* Grabber + ); + +/// @ingroup GRABBER_CTRL +/// \~chinese +/// \brief ֹͣɼ +/// \param [in] Grabber ɼ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \warning ڲȴлصŷص,ڵȴʱɷwindowsϢ +/// \~english +/// \brief Stop Grabber +/// \param [in] Grabber +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \warning This function will wait for all callbacks to end before returning to the caller,And it will dispatch windows messages while waiting. +MVSDK_API CameraSdkStatus __stdcall CameraGrabber_StopLive( + void* Grabber + ); + +/// @ingroup GRABBER_SNAPSHOT +/// \~chinese +/// \brief ͬץͼ +/// \param [in] Grabber ɼ +/// \param [out] Image ץȡͼ \note Ҫ@link #CameraImage_Destroy @endlinkͷ +/// \param [in] TimeOut ʱʱ䣨룩 +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Synchronized snapshot +/// \param [in] Grabber +/// \param [out] Image Returns Captured Image \note Need to Call @link #CameraImage_Destroy @endlink Release +/// \param [in] TimeOut Timeout (milliseconds) +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGrabber_SaveImage( + void* Grabber, + void** Image, + DWORD TimeOut + ); + +/// @ingroup GRABBER_SNAPSHOT +/// \~chinese +/// \brief ύһ첽ץͼύɹץͼɻصûõɺ +/// \param [in] Grabber ɼ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \see CameraGrabber_SetSaveImageCompleteCallback +/// \~english +/// \brief Submit an asynchronous snapshot request, complete the user's completion function after the completion of the submission. +/// \param [in] Grabber +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \see CameraGrabber_SetSaveImageCompleteCallback +MVSDK_API CameraSdkStatus __stdcall CameraGrabber_SaveImageAsync( + void* Grabber + ); + +/// @ingroup GRABBER_SNAPSHOT +/// \~chinese +/// \brief ύһ첽ץͼύɹץͼɻصûõɺ +/// \param [in] Grabber ɼ +/// \param [in] UserData ûݣʹ @link CameraImage_GetUserData @endlink Imageȡֵ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \see CameraGrabber_SetSaveImageCompleteCallback +/// \~english +/// \brief Submit an asynchronous snapshot request, complete the user's completion function after the completion of the submission. +/// \param [in] Grabber +/// \param [in] UserData user data, which can be obtained from Image using @link CameraImage_GetUserData @endlink +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \see CameraGrabber_SetSaveImageCompleteCallback +MVSDK_API CameraSdkStatus __stdcall CameraGrabber_SaveImageAsyncEx( + void* Grabber, + void* UserData + ); + +/// @ingroup GRABBER_SNAPSHOT +/// \~chinese +/// \brief 첽ʽץͼɺ +/// \param [in] Grabber ɼ +/// \param [in] Callback 첽ץͼʱ +/// \param [in] Context CallbackʱΪCallback +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \see CameraGrabber_SaveImageAsync CameraGrabber_SaveImageAsyncEx +/// \~english +/// \brief Set the completion function of asynchronous mode snapshot +/// \param [in] Grabber +/// \param [in] Callback Callback is called when the asynchronous snapshot task completes +/// \param [in] Context Passed as a parameter when the Callback is invoked +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +/// \see CameraGrabber_SaveImageAsync CameraGrabber_SaveImageAsyncEx +MVSDK_API CameraSdkStatus __stdcall CameraGrabber_SetSaveImageCompleteCallback( + void* Grabber, + pfnCameraGrabberSaveImageComplete Callback, + void* Context + ); + +/// @ingroup GRABBER_CB +/// \~chinese +/// \brief ֡ +/// \param [in] Grabber ɼ +/// \param [in] Listener +/// \param [in] Context ListenerʱΪListener +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set frame listening function +/// \param [in] Grabber +/// \param [in] Listener listener function +/// \param [in] Context Passed as a parameter when the Listener is invoked +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGrabber_SetFrameListener( + void* Grabber, + pfnCameraGrabberFrameListener Listener, + void* Context + ); + +/// @ingroup GRABBER_CB +/// \~chinese +/// \brief RAWݻص +/// \param [in] Grabber ɼ +/// \param [in] Callback Rawص +/// \param [in] Context CallbackʱΪCallback +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set RAW data callback function +/// \param [in] Grabber +/// \param [in] Callback Raw data callback function +/// \param [in] Context Passed as a parameter when the Callback is invoked +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGrabber_SetRawCallback( + void* Grabber, + pfnCameraGrabberFrameCallback Callback, + void* Context + ); + +/// @ingroup GRABBER_CB +/// \~chinese +/// \brief RGBص +/// \param [in] Grabber ɼ +/// \param [in] Callback RGBص +/// \param [in] Context CallbackʱΪCallback +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set RGB callback function +/// \param [in] Grabber +/// \param [in] Callback RGB data callback function +/// \param [in] Context Passed as a parameter when the Callback is invoked +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGrabber_SetRGBCallback( + void* Grabber, + pfnCameraGrabberFrameCallback Callback, + void* Context + ); + +/// @ingroup GRABBER_CTRL +/// \~chinese +/// \brief ȡ +/// \param [in] Grabber ɼ +/// \param [out] hCamera ص +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get camera handle +/// \param [in] Grabber +/// \param [out] hCamera returned camera handle +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGrabber_GetCameraHandle( + void* Grabber, + CameraHandle *hCamera + ); + +/// @ingroup GRABBER_CTRL +/// \~chinese +/// \brief ȡ֡ͳϢ +/// \param [in] Grabber ɼ +/// \param [out] stat صͳϢ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get frame statistics +/// \param [in] Grabber +/// \param [out] stat returned statistics +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGrabber_GetStat( + void* Grabber, + tSdkGrabberStat *stat + ); + +/// @ingroup GRABBER_CTRL +/// \~chinese +/// \brief ȡDevInfo +/// \param [in] Grabber ɼ +/// \param [out] DevInfo صDevInfo +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get Camera DevInfo +/// \param [in] Grabber +/// \param [out] DevInfo Returns Camera DevInfo +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraGrabber_GetCameraDevInfo( + void* Grabber, + tSdkCameraDevInfo *DevInfo + ); + + + + +#endif // _MV_CAMERA_GRABBER_H_ diff --git a/others/include/camera/CameraImage.h b/others/include/camera/CameraImage.h new file mode 100644 index 0000000..536d38b --- /dev/null +++ b/others/include/camera/CameraImage.h @@ -0,0 +1,380 @@ +#ifndef _MV_CAMERA_IMAGE_H_ +#define _MV_CAMERA_IMAGE_H_ + +#include "CameraDefine.h" +#include "CameraStatus.h" + + +/// @ingroup MV_IMAGE +/// \~chinese +/// \brief һµImage +/// \param [out] Image ´ͼƬ +/// \param [in] pFrameBuffer ֡ +/// \param [in] pFrameHead ֡ͷ +/// \param [in] bCopy TRUE: Ƴһµ֡ FALSE: ƣֱʹpFrameBufferָĻ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Create a new Image +/// \param [out] Image Newly Created Image +/// \param [in] pFrameBuffer frame data +/// \param [in] pFrameHead Frame Header +/// \param [in] bCopy TRUE: Copy a new frame data FALSE: Do not copy, directly use the buffer pointed to by pFrameBuffer +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImage_Create( + void** Image, + BYTE *pFrameBuffer, + tSdkFrameHead* pFrameHead, + BOOL bCopy + ); + +/// @ingroup MV_IMAGE +/// \~chinese +/// \brief һյImage +/// \param [out] Image ´ͼƬ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Create an empty Image +/// \param [out] Image Newly Created Image +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImage_CreateEmpty( + void** Image + ); + +/// @ingroup MV_IMAGE +/// \~chinese +/// \brief Image +/// \param [in] Image +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Destroy Image +/// \param [in] Image +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImage_Destroy( + void* Image + ); + +/// @ingroup MV_IMAGE +/// \~chinese +/// \brief Imageȡ֡ݺ֡ͷ +/// \param [in] Image +/// \param [out] DataBuffer ֡ +/// \param [out] Head ֡ͷ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get frame data and frame header from Image +/// \param [in] Image +/// \param [out] DataBuffer Frame Data +/// \param [out] Head header +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImage_GetData( + void* Image, + BYTE** DataBuffer, + tSdkFrameHead** Head + ); + +/// @ingroup MV_IMAGE +/// \~chinese +/// \brief ȡImageûԶ +/// \param [in] Image +/// \param [out] UserData ûԶ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Get User's Custom Data of Image +/// \param [in] Image +/// \param [out] UserData returns user-defined data +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImage_GetUserData( + void* Image, + void** UserData + ); + +/// @ingroup MV_IMAGE +/// \~chinese +/// \brief ImageûԶ +/// \param [in] Image +/// \param [in] UserData ûԶ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Set user-defined data for Image +/// \param [in] Image +/// \param [in] UserData User-defined data +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImage_SetUserData( + void* Image, + void* UserData + ); + +/// @ingroup MV_IMAGE +/// \~chinese +/// \brief жһImageǷΪ +/// \param [in] Image +/// \param [out] IsEmpty Ϊշ:TRUE(1) 򷵻:FALSE(0) +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Determine if an Image is empty +/// \param [in] Image +/// \param [out] IsEmpty Empty Returns: TRUE(1) Otherwise returns: FALSE(0) +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImage_IsEmpty( + void* Image, + BOOL* IsEmpty + ); + +/// @ingroup MV_IMAGE +/// \~chinese +/// \brief Imageָ +/// \param [in] Image +/// \param [in] hWnd ĿĴ +/// \param [in] Algorithm 㷨 0ٵԲ 1ٶ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Draw Image to the specified window +/// \param [in] Image +/// \param [in] hWnd destination window +/// \param [in] Algorithm scaling algorithm 0:fast but slightly worse quality 1:slower but better quality +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImage_Draw( + void* Image, + HWND hWnd, + int Algorithm + ); + +/// @ingroup MV_IMAGE +/// \~chinese +/// \brief Imageָ +/// \param [in] Image +/// \param [in] hWnd ĿĴ +/// \param [in] Algorithm 㷨 0ٵԲ 1ٶ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Pull up drawing Image to the specified window +/// \param [in] Image +/// \param [in] hWnd destination window +/// \param [in] Algorithm scaling algorithm 0:fast but slightly worse quality 1:slower but better quality +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImage_DrawFit( + void* Image, + HWND hWnd, + int Algorithm + ); + +/// @ingroup MV_IMAGE +/// \~chinese +/// \brief ImageָDC +/// \param [in] Image +/// \param [in] hDC ĿDC +/// \param [in] Algorithm 㷨 0ٵԲ 1ٶ +/// \param [in] xDst ĿεϽX +/// \param [in] yDst ĿεϽY +/// \param [in] cxDst ĿεĿ +/// \param [in] cyDst Ŀεĸ߶ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Draw Image to specified DC +/// \param [in] Image +/// \param [in] hDC destination DC +/// \param [in] Algorithm scaling algorithm 0:fast but slightly worse quality 1:slower but better quality +/// \param [in] xDst The X coordinate of the upper left corner of the target rectangle +/// \param [in] yDst The Y coordinate of the upper left corner of the target rectangle +/// \param [in] cxDst Width of target rectangle +/// \param [in] cyDst Height of target rectangle +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImage_DrawToDC( + void* Image, + HDC hDC, + int Algorithm, + int xDst, + int yDst, + int cxDst, + int cyDst + ); + +/// @ingroup MV_IMAGE +/// \~chinese +/// \brief ImageָDC +/// \param [in] Image +/// \param [in] hDC ĿDC +/// \param [in] Algorithm 㷨 0ٵԲ 1ٶ +/// \param [in] xDst ĿεϽX +/// \param [in] yDst ĿεϽY +/// \param [in] cxDst ĿεĿ +/// \param [in] cyDst Ŀεĸ߶ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Pull up drawing Image to specified DC +/// \param [in] Image +/// \param [in] hDC destination DC +/// \param [in] Algorithm scaling algorithm 0:fast but slightly worse quality 1:slower but better quality +/// \param [in] xDst The X coordinate of the upper left corner of the target rectangle +/// \param [in] yDst The Y coordinate of the upper left corner of the target rectangle +/// \param [in] cxDst Width of target rectangle +/// \param [in] cyDst Height of target rectangle +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImage_DrawToDCFit( + void* Image, + HDC hDC, + int Algorithm, + int xDst, + int yDst, + int cxDst, + int cyDst + ); + +/// @ingroup MV_IMAGE +/// \~chinese +/// \brief Imageָڣţ +/// \param [in] Image +/// \param [in] hWnd ĿĴ +/// \param [in] xDst ĿεϽX +/// \param [in] yDst ĿεϽY +/// \param [in] cxDst ĿεĿ +/// \param [in] cyDst Ŀεĸ߶ +/// \param [in] xSrc ͼεϽX +/// \param [in] ySrc ͼεϽY +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Draw Image to specified window (without scaling) +/// \param [in] Image +/// \param [in] hWnd destination window +/// \param [in] xDst The X coordinate of the upper left corner of the target rectangle +/// \param [in] yDst The Y coordinate of the upper left corner of the target rectangle +/// \param [in] cxDst Width of target rectangle +/// \param [in] cyDst Height of target rectangle +/// \param [in] xSrc X coordinate of the upper left corner of the image rectangle +/// \param [in] ySrc Y coordinate of the upper left corner of the image rectangle +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImage_BitBlt( + void* Image, + HWND hWnd, + int xDst, + int yDst, + int cxDst, + int cyDst, + int xSrc, + int ySrc + ); + +/// @ingroup MV_IMAGE +/// \~chinese +/// \brief ImageָDCţ +/// \param [in] Image +/// \param [in] hDC ĿDC +/// \param [in] xDst ĿεϽX +/// \param [in] yDst ĿεϽY +/// \param [in] cxDst ĿεĿ +/// \param [in] cyDst Ŀεĸ߶ +/// \param [in] xSrc ͼεϽX +/// \param [in] ySrc ͼεϽY +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Draw Image to specified DC (without scaling) +/// \param [in] Image +/// \param [in] hDC destination DC +/// \param [in] xDst The X coordinate of the upper left corner of the target rectangle +/// \param [in] yDst The Y coordinate of the upper left corner of the target rectangle +/// \param [in] cxDst Width of target rectangle +/// \param [in] cyDst Height of target rectangle +/// \param [in] xSrc X coordinate of the upper left corner of the image rectangle +/// \param [in] ySrc Y coordinate of the upper left corner of the image rectangle +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImage_BitBltToDC( + void* Image, + HDC hDC, + int xDst, + int yDst, + int cxDst, + int cyDst, + int xSrc, + int ySrc + ); + +/// @ingroup MV_IMAGE +/// \~chinese +/// \brief bmpʽImage +/// \param [in] Image +/// \param [in] FileName ļ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Save Image as bmp +/// \param [in] Image +/// \param [in] FileName file name +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImage_SaveAsBmp( + void* Image, + char const* FileName + ); + +/// @ingroup MV_IMAGE +/// \~chinese +/// \brief jpgʽImage +/// \param [in] Image +/// \param [in] FileName ļ +/// \param [in] Quality (1-100)100ΪѵļҲ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Save Image as jpg +/// \param [in] Image +/// \param [in] FileName file name +/// \param [in] Quality save quality (1-100), 100 is the best quality but the file is also the largest +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImage_SaveAsJpeg( + void* Image, + char const* FileName, + BYTE Quality + ); + +/// @ingroup MV_IMAGE +/// \~chinese +/// \brief pngʽImage +/// \param [in] Image +/// \param [in] FileName ļ +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Save Image as png +/// \param [in] Image +/// \param [in] FileName file name +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImage_SaveAsPng( + void* Image, + char const* FileName + ); + +/// @ingroup MV_IMAGE +/// \~chinese +/// \brief rawʽImage +/// \param [in] Image +/// \param [in] FileName ļ +/// \param [in] Format 0: 8Bit Raw 1: 16Bit Raw +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Save Image as raw +/// \param [in] Image +/// \param [in] FileName file name +/// \param [in] Format 0: 8Bit Raw 1: 16Bit Raw +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImage_SaveAsRaw( + void* Image, + char const* FileName, + int Format + ); + +/// @ingroup MV_IMAGE +/// \~chinese +/// \brief ImageһIPicture +/// \param [in] Image +/// \param [out] NewPic ´IPicture +/// \return ɹ CAMERA_STATUS_SUCCESS(0)򷵻ط0ֵĴ, ο CameraStatus.h дĶ塣 +/// \~english +/// \brief Create an IPicture from an Image +/// \param [in] Image +/// \param [out] NewPic Newly created IPicture +/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h. +MVSDK_API CameraSdkStatus __stdcall CameraImage_IPicture( + void* Image, + IPicture** NewPic + ); + + + + +#endif // _MV_CAMERA_IMAGE_H_ diff --git a/others/include/camera/CameraStatus.h b/others/include/camera/CameraStatus.h new file mode 100644 index 0000000..4ea675f --- /dev/null +++ b/others/include/camera/CameraStatus.h @@ -0,0 +1,114 @@ +#ifndef __CAMERA_STATUS_DEF__ +#define __CAMERA_STATUS_DEF__ + +/// @ingroup MV_TYPEDEF +/// \~chinese SDK +/// \~english SDK error code +typedef int CameraSdkStatus; + + +/*õĺ*/ +#define SDK_SUCCESS(_FUC_) (_FUC_ == CAMERA_STATUS_SUCCESS) + +#define SDK_UNSUCCESS(_FUC_) (_FUC_ != CAMERA_STATUS_SUCCESS) + +#define SDK_UNSUCCESS_RETURN(_FUC_,RET) if((RET = _FUC_) != CAMERA_STATUS_SUCCESS)\ + {\ + return RET;\ + } + +#define SDK_UNSUCCESS_BREAK(_FUC_) if(_FUC_ != CAMERA_STATUS_SUCCESS)\ + {\ + break;\ + } + + +/// @ingroup MV_MACRO_TYPE +/// @{ +/* ô */ + +#define CAMERA_STATUS_SUCCESS 0 ///< \~chinese ɹ \~english Successful +#define CAMERA_STATUS_FAILED -1 ///< \~chinese ʧ \~english operation failed +#define CAMERA_STATUS_INTERNAL_ERROR -2 ///< \~chinese ڲ \~english internal error +#define CAMERA_STATUS_UNKNOW -3 ///< \~chinese δ֪ \~english unknown error +#define CAMERA_STATUS_NOT_SUPPORTED -4 ///< \~chinese ָ֧ù \~english Does not support this feature +#define CAMERA_STATUS_NOT_INITIALIZED -5 ///< \~chinese ʼδ \~english Incomplete initialization +#define CAMERA_STATUS_PARAMETER_INVALID -6 ///< \~chinese Ч \~english Invalid argument +#define CAMERA_STATUS_PARAMETER_OUT_OF_BOUND -7 ///< \~chinese Խ \~english Out of bounds of parameters +#define CAMERA_STATUS_UNENABLED -8 ///< \~chinese δʹ \~english Not enabled +#define CAMERA_STATUS_USER_CANCEL -9 ///< \~chinese ûֶȡˣroiȡ \~english The user manually canceled, such as roi panel click cancel, return +#define CAMERA_STATUS_PATH_NOT_FOUND -10 ///< \~chinese עûҵӦ· \~english The corresponding path was not found in the registry +#define CAMERA_STATUS_SIZE_DISMATCH -11 ///< \~chinese ͼݳȺͶijߴ粻ƥ \~english The length of the obtained image data does not match the defined size +#define CAMERA_STATUS_TIME_OUT -12 ///< \~chinese ʱ \~english Timeout error +#define CAMERA_STATUS_IO_ERROR -13 ///< \~chinese ӲIO \~english Hardware IO error +#define CAMERA_STATUS_COMM_ERROR -14 ///< \~chinese ͨѶ \~english Communication error +#define CAMERA_STATUS_BUS_ERROR -15 ///< \~chinese ߴ \~english Bus error +#define CAMERA_STATUS_NO_DEVICE_FOUND -16 ///< \~chinese ûз豸 \~english No device found +#define CAMERA_STATUS_NO_LOGIC_DEVICE_FOUND -17 ///< \~chinese δҵ߼豸 \~english Logical device not found +#define CAMERA_STATUS_DEVICE_IS_OPENED -18 ///< \~chinese 豸Ѿ \~english The device is already open +#define CAMERA_STATUS_DEVICE_IS_CLOSED -19 ///< \~chinese 豸Ѿر \~english Device is off +#define CAMERA_STATUS_DEVICE_VEDIO_CLOSED -20 ///< \~chinese ûд豸Ƶ¼صĺʱƵûд򿪣طظô \~english Without opening the device video, when the video-related function is called, if the camera video is not open, the error is returned back. +#define CAMERA_STATUS_NO_MEMORY -21 ///< \~chinese û㹻ϵͳڴ \~english Not enough system memory +#define CAMERA_STATUS_FILE_CREATE_FAILED -22 ///< \~chinese ļʧ \~english Failed to create file +#define CAMERA_STATUS_FILE_INVALID -23 ///< \~chinese ļʽЧ \~english Invalid file format +#define CAMERA_STATUS_WRITE_PROTECTED -24 ///< \~chinese дд \~english Write protection, not write +#define CAMERA_STATUS_GRAB_FAILED -25 ///< \~chinese ݲɼʧ \~english Data collection failed +#define CAMERA_STATUS_LOST_DATA -26 ///< \~chinese ݶʧ \~english Loss of data, incomplete +#define CAMERA_STATUS_EOF_ERROR -27 ///< \~chinese δյ֡ \~english No frame terminator received +#define CAMERA_STATUS_BUSY -28 ///< \~chinese æ(һβڽ)˴βܽ \~english Busy (last operation is still in progress), this operation cannot be performed +#define CAMERA_STATUS_WAIT -29 ///< \~chinese Ҫȴ(в)ٴγ \~english Need to wait (condition of operation is not established), can try again +#define CAMERA_STATUS_IN_PROCESS -30 ///< \~chinese ڽУѾ \~english Ongoing, has been operated +#define CAMERA_STATUS_IIC_ERROR -31 ///< \~chinese IIC \~english IIC transmission error +#define CAMERA_STATUS_SPI_ERROR -32 ///< \~chinese SPI \~english SPI transmission error +#define CAMERA_STATUS_USB_CONTROL_ERROR -33 ///< \~chinese USBƴ \~english USB control transmission error +#define CAMERA_STATUS_USB_BULK_ERROR -34 ///< \~chinese USB BULK \~english USB BULK transmission error +#define CAMERA_STATUS_SOCKET_INIT_ERROR -35 ///< \~chinese 紫׼ʼʧ \~english Network Transport Suite Initialization Failed +#define CAMERA_STATUS_GIGE_FILTER_INIT_ERROR -36 ///< \~chinese ں˹ʼʧܣǷȷװ°װ \~english The webcam kernel filter driver failed to initialize. Please check if the driver is installed correctly or reinstall it. +#define CAMERA_STATUS_NET_SEND_ERROR -37 ///< \~chinese ݷʹ \~english Network data sending error +#define CAMERA_STATUS_DEVICE_LOST -38 ///< \~chinese ʧȥӣⳬʱ \~english Lost connection with webcam, heartbeat timeout +#define CAMERA_STATUS_DATA_RECV_LESS -39 ///< \~chinese յֽ \~english Received fewer bytes than requested +#define CAMERA_STATUS_FUNCTION_LOAD_FAILED -40 ///< \~chinese ļмسʧ \~english Failed to load program from file +#define CAMERA_STATUS_CRITICAL_FILE_LOST -41 ///< \~chinese ļʧ \~english The file necessary to run the program is missing. +#define CAMERA_STATUS_SENSOR_ID_DISMATCH -42 ///< \~chinese ̼ͳƥ䣬ԭ˴Ĺ̼ \~english The firmware and program do not match because the wrong firmware was downloaded. +#define CAMERA_STATUS_OUT_OF_RANGE -43 ///< \~chinese ЧΧ \~english The parameter is out of valid range. +#define CAMERA_STATUS_REGISTRY_ERROR -44 ///< \~chinese װע°װ򣬻аװĿ¼Setup/Installer.exe \~english Setup registration error. Please reinstall the program, or run the installation directory Setup/Installer.exe +#define CAMERA_STATUS_ACCESS_DENY -45 ///< \~chinese ֹʡָѾռʱʸ᷵ظ״̬(һܱͬʱ) \~english No Access. When the specified camera has been occupied by another program, it will return to this state if you request to access the camera. (A camera cannot be accessed simultaneously by multiple programs) +#define CAMERA_STATUS_CAMERA_NEED_RESET -46 ///< \~chinese ʾҪλʹãʱϵϵͳ󣬱ʹá \~english It means that the camera needs to be reset before it can be used normally. At this time, please make the camera power off and restart, or restart the operating system, then it can be used normally. +#define CAMERA_STATUS_ISP_MOUDLE_NOT_INITIALIZED -47 ///< \~chinese ISPģδʼ \~english ISP module is not initialized +#define CAMERA_STATUS_ISP_DATA_CRC_ERROR -48 ///< \~chinese У \~english Data check error +#define CAMERA_STATUS_MV_TEST_FAILED -49 ///< \~chinese ݲʧ \~english Data test failed +#define CAMERA_STATUS_INTERNAL_ERR1 -50 ///< \~chinese ڲ1 \~english Internal error 1 +#define CAMERA_STATUS_U3V_NO_CONTROL_EP -51 ///< \~chinese U3Vƶ˵δҵ \~english U3V control endpoint not found +#define CAMERA_STATUS_U3V_CONTROL_ERROR -52 ///< \~chinese U3VͨѶ \~english U3V control communication error +#define CAMERA_STATUS_INVALID_FRIENDLY_NAME -53 ///< \~chinese Ч豸ﲻַܰ(\/:*?"<>|") \~english Invalid device name, the name cannot contain the following characters (\/:*?"<>|") + + + +//AIAƶı׼ͬ +/*#define CAMERA_AIA_SUCCESS 0x0000 */ +#define CAMERA_AIA_PACKET_RESEND 0x0100 ///< \~chinese ֡Ҫش \~english The frame needs to be retransmitted +#define CAMERA_AIA_NOT_IMPLEMENTED 0x8001 ///< \~chinese 豸ֵ֧ \~english Device does not support commands +#define CAMERA_AIA_INVALID_PARAMETER 0x8002 ///< \~chinese Ƿ \~english Illegal command parameters +#define CAMERA_AIA_INVALID_ADDRESS 0x8003 ///< \~chinese ɷʵĵַ \~english Inaccessible address +#define CAMERA_AIA_WRITE_PROTECT 0x8004 ///< \~chinese ʵĶ󲻿д \~english The accessed object cannot be written +#define CAMERA_AIA_BAD_ALIGNMENT 0x8005 ///< \~chinese ʵĵַûаҪ \~english Visited address is not aligned as required +#define CAMERA_AIA_ACCESS_DENIED 0x8006 ///< \~chinese ûзȨ \~english No access +#define CAMERA_AIA_BUSY 0x8007 ///< \~chinese ڴ \~english Command is processing +#define CAMERA_AIA_DEPRECATED 0x8008 ///< \~chinese 0x8008-0x0800B 0x800F ָѾ \~english 0x8008-0x0800B 0x800F This instruction has been deprecated +#define CAMERA_AIA_PACKET_UNAVAILABLE 0x800C ///< \~chinese Ч \~english Invalid package +#define CAMERA_AIA_DATA_OVERRUN 0x800D ///< \~chinese ͨյݱҪĶ \~english Data overflow, usually more data than needed +#define CAMERA_AIA_INVALID_HEADER 0x800E ///< \~chinese ݰͷijЩЭ鲻ƥ \~english Some areas in the packet header do not match the protocol +#define CAMERA_AIA_PACKET_NOT_YET_AVAILABLE 0x8010 ///< \~chinese ͼְݻδ׼ãڴģʽӦóʳʱ \~english Image packet data is not ready yet. It is mostly used in trigger mode. Application access timeout +#define CAMERA_AIA_PACKET_AND_PREV_REMOVED_FROM_MEMORY 0x8011 ///< \~chinese ҪʵķְѾڡشʱѾڻ \~english Subcontracts that require access no longer exist. Mostly used for data retransmission is not in the buffer +#define CAMERA_AIA_PACKET_REMOVED_FROM_MEMORY 0x8012 ///< \~chinese CAMERA_AIA_PACKET_AND_PREV_REMOVED_FROM_MEMORY \~english CAMERA_AIA_PACKET_AND_PREV_REMOVED_FROM_MEMORY +#define CAMERA_AIA_NO_REF_TIME 0x0813 ///< \~chinese ûвοʱԴʱִͬʱ \~english There is no reference clock source. When used for time synchronization commands +#define CAMERA_AIA_PACKET_TEMPORARILY_UNAVAILABLE 0x0814 ///< \~chinese ŵ⣬ǰְʱãԺз \~english Due to channel bandwidth issues, the current subcontracting is temporarily unavailable and needs to be accessed later +#define CAMERA_AIA_OVERFLOW 0x0815 ///< \~chinese 豸ͨǶ \~english Data overflow on the device, usually the queue is full +#define CAMERA_AIA_ACTION_LATE 0x0816 ///< \~chinese ִѾЧָʱ \~english Command execution has exceeded valid specified time +#define CAMERA_AIA_ERROR 0x8FFF ///< \~chinese \~english error + +/// @} end of MV_MACRO_TYPE + + + +#endif diff --git a/others/include/camera/camera_define.h b/others/include/camera/camera_define.h index ba7d937..eeedb6c 100644 --- a/others/include/camera/camera_define.h +++ b/others/include/camera/camera_define.h @@ -14,21 +14,22 @@ typedef unsigned int UINT; typedef unsigned long long UINT64; typedef int BOOL; typedef unsigned char BYTE; -typedef unsigned int DWORD; +#define DWORD unsigned int typedef void* PVOID; -typedef void* HWND; -typedef char* LPCTSTR; +#define HWND typedef void* +#define LPCTSTR char* typedef unsigned short USHORT; typedef short SHORT; typedef unsigned char* LPBYTE; typedef char CHAR; -typedef short WORD; -typedef INT HANDLE; -typedef void VOID; +#define WORD short +#define HANDLE INT +#define VOID void typedef unsigned long ULONG; -typedef void** LPVOID; +#define LPVOID void** typedef unsigned char UCHAR; -typedef void* HMODULE; +#define HMODULE void* + #define TRUE 1 #define FALSE 0 diff --git a/others/include/camera/camera_wrapper.h b/others/include/camera/camera_wrapper.h index 40bfd4e..209465f 100644 --- a/others/include/camera/camera_wrapper.h +++ b/others/include/camera/camera_wrapper.h @@ -14,7 +14,7 @@ #include #include "camera/wrapper_head.h" -#include "camera/camera_api.h" +#include "camera/CameraApi.h" class CameraWrapper: public WrapperHead { private: diff --git a/others/include/log.h b/others/include/log.h index ed7fd62..2e9d6f1 100644 --- a/others/include/log.h +++ b/others/include/log.h @@ -6,7 +6,6 @@ #define _LOG_H_ #include -#include /************** Define the control code *************/ #define START_CTR "\033[0" @@ -125,17 +124,29 @@ __FILE__, __LINE__, ##__VA_ARGS__) /******************** the time counter API ************************/ -#if LOG_LEVEL > LOG_NONE && (!defined(DO_NOT_CNT_TIME)) - #define CNT_TIME(str_ctrs, tag, codes, ...) do{\ - timeval ts, te; \ - gettimeofday(&ts, NULL); \ - codes; \ - gettimeofday(&te, NULL); \ - LOGM(STR_CTR(str_ctrs, tag": %fms"), ## __VA_ARGS__, (te.tv_sec-ts.tv_sec)*1000.0 + (te.tv_usec-ts.tv_usec)/1000.0); \ - }while(0) +#ifndef DO_NOT_CNT_TIME && LOG_LEVEL > LOG_NONE + #ifdef WIN32 + #include + #define CNT_TIME(tag, codes, ...) do{ \ + static SYSTEMTIME ts, te; \ + GetLocalTime(&ts); \ + codes; \ + GetLocalTime(&te); \ + LOGM(tag": %dms", (te.wSecond-ts.wSecond)*1000+(te.wMilliseconds-ts.wMilliseconds)); \ + }while (0) + #else + #include + #define CNT_TIME(tag, codes, ...) do{ \ + static timeval ts, te; \ + gettimeofday(&ts); \ + codes; \ + gettimeofday(&te); \ + LOGM(tag": %.1lfms", (te.tv_sec-ts.tv_sec)*1000.0+(te.tv_usec-ts.tv_usec)/1000.0); \ + }while (0) + #endif #else - #define CNT_TIME(str_ctrs, tag, codes, ...) codes + #define CNT_TIME(tag, codes, ...) codes #endif #else /* _LOG_H_ */ #warning "Multiple include of log.h, some settings may not work." -#endif /* _LOG_H_ */ +#endif /* _LOG_H_ */ diff --git a/others/include/options/options.h b/others/include/options/options.h index 5563a0a..b1285f3 100644 --- a/others/include/options/options.h +++ b/others/include/options/options.h @@ -5,6 +5,7 @@ #ifndef _OPTIONS_H_ #define _OPTIONS_H_ +#define PROJECT_DIR PATH extern bool show_armor_box; extern bool show_armor_boxes; diff --git a/others/include/serial/serial.h b/others/include/serial/serial.h new file mode 100644 index 0000000..4a98040 --- /dev/null +++ b/others/include/serial/serial.h @@ -0,0 +1,30 @@ +#ifndef _SERIAL_H_ +#define _SERIAL_H_ + +#include + +class Serial +{ +public: + Serial(UINT portNo = 1, UINT baud = CBR_9600, char parity = 'N', UINT databits = 8, UINT stopsbits = 1, DWORD dwCommEvents = EV_RXCHAR); + ~Serial(); + + bool InitPort(UINT portNo = 1, UINT baud = CBR_9600, char parity = 'N', UINT databits = 8, UINT stopsbits = 1, DWORD dwCommEvents = EV_RXCHAR); + UINT GetBytesInCOM() const ; + bool WriteData(const unsigned char* pData, unsigned int length); + bool ReadData(unsigned char* buffer, unsigned int length); +private: + bool openPort(UINT portNo); + void ClosePort(); + void ErrorHandler(); +private: + HANDLE hComm; + UINT portNo; + UINT baud; + char parity; + UINT databits; + UINT stopsbits; + DWORD dwCommEvents; +}; + +#endif /* _SERIAL_H_ */ diff --git a/others/include/uart/uart.h b/others/include/uart/uart.h deleted file mode 100644 index c0a452e..0000000 --- a/others/include/uart/uart.h +++ /dev/null @@ -1,42 +0,0 @@ -// -// Created by xixiliadorabarry on 1/24/19. -// - -#ifndef STEREOVISION_UART_H -#define STEREOVISION_UART_H - -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include - -//#include - - - -class Uart { -private: - int fd; - char buff[8]; - int fps; - time_t cur_time; - - int set_opt(int fd, int nSpeed, int nBits, char nEvent, int nStop); - -public: - Uart(); - void sendTarget(float x, float y ,float z); - - uint8_t receive(); - void receive_data(); -}; - - -#endif //STEREOVISION_UART_H diff --git a/others/src/camera/camera_wrapper.cpp b/others/src/camera/camera_wrapper.cpp index e765b1e..8ed2052 100644 --- a/others/src/camera/camera_wrapper.cpp +++ b/others/src/camera/camera_wrapper.cpp @@ -4,6 +4,9 @@ #include #include +#include + +using namespace std; using std::cout; using std::endl; @@ -22,20 +25,16 @@ CameraWrapper::CameraWrapper(int camera_mode, const std::string &n): bool CameraWrapper::init() { CameraSdkInit(1); - - //枚举设备,并建立设备列表 - int camera_enumerate_device_status = CameraEnumerateDevice(camera_enum_list, &camera_cnts); + int camera_enumerate_device_status = CameraEnumerateDevice(camera_enum_list, &camera_cnts); if(camera_enumerate_device_status != CAMERA_STATUS_SUCCESS){ LOGE("CameraEnumerateDevice fail with %d!", camera_enumerate_device_status); } - //没有连接设备 if (camera_cnts == 0) { LOGE("No camera device detected!"); return false; }else if(camera_cnts >= 1){ LOGM("%d camera device detected!", camera_cnts); } - //相机初始化。初始化成功后,才能调用任何其他相机相关的操作接口 int i; for(i=0; i +#include +#include +using namespace std; +#include + +Serial::Serial(UINT portNo, UINT baud, char parity, UINT databits, UINT stopsbits, DWORD dwCommEvents) : +hComm(INVALID_HANDLE_VALUE), +portNo(portNo), +parity(parity), +databits(databits), +stopsbits(stopsbits), +dwCommEvents(dwCommEvents){ + if (wait_uart) { + LOGM("Waiting for serial COM%d", portNo); + while (InitPort(portNo, baud, parity, databits, stopsbits, dwCommEvents) == false); + LOGM("Port COM%d open success!", portNo); + } else { + if (InitPort(portNo, baud, parity, databits, stopsbits, dwCommEvents)) { + LOGM("Port COM%d open success!", portNo); + } else { + LOGE("Port COM%d open fail!", portNo); + } + } +} + +Serial::~Serial() { + ClosePort(); +} + +void Serial::ErrorHandler() { + if (wait_uart) { + LOGE("Serial COM%d offline, waiting for serial COM%d", portNo, portNo); + while (InitPort(portNo, baud, parity, databits, stopsbits, dwCommEvents) == false); + LOGM("Port COM%d reopen success!", portNo); + } +} + +bool Serial::openPort(UINT portNo) { + char szPort[50]; + sprintf_s(szPort, "COM%d", portNo); + + /** ָĴ */ + hComm = CreateFileA(szPort, /** 豸,COM1,COM2 */ + GENERIC_READ | GENERIC_WRITE, /** ģʽ,ͬʱд */ + 0, /** ģʽ,0ʾ */ + NULL, /** ȫ,һʹNULL */ + OPEN_EXISTING, /** òʾ豸,򴴽ʧ */ + 0, + 0); + + return hComm != INVALID_HANDLE_VALUE; +} + +void Serial::ClosePort() { + /** дڱ򿪣ر */ + if (hComm != INVALID_HANDLE_VALUE) { + CloseHandle(hComm); + hComm = INVALID_HANDLE_VALUE; + } +} + +bool Serial::InitPort(UINT portNo, UINT baud, char parity, UINT databits, UINT stopsbits, DWORD dwCommEvents) { + /** ʱ,ƶתΪַʽ,ԹDCBṹ */ + char szDCBparam[50]; + sprintf_s(szDCBparam, "baud=%d parity=%c data=%d stop=%d", baud, parity, databits, stopsbits); + + if (!openPort(portNo)){ + cout << "open error!" << endl; + return false; + } + + BOOL bIsSuccess = TRUE; + COMMTIMEOUTS CommTimeouts; + CommTimeouts.ReadIntervalTimeout = 0; + CommTimeouts.ReadTotalTimeoutMultiplier = 0; + CommTimeouts.ReadTotalTimeoutConstant = 0; + CommTimeouts.WriteTotalTimeoutMultiplier = 0; + CommTimeouts.WriteTotalTimeoutConstant = 0; + if (bIsSuccess) { + bIsSuccess = SetCommTimeouts(hComm, &CommTimeouts); + } else { + cout << "SetCommTimeouts error!" << endl; + } + + DCB dcb; + if (bIsSuccess) { + /** ȡǰò,ҹ촮DCB */ + bIsSuccess = GetCommState(hComm, &dcb); + bIsSuccess = BuildCommDCB(szDCBparam, &dcb); + if (!bIsSuccess) { + + cout << "Create dcb fail with "<< GetLastError() << endl; + } + /** RTS flow */ + dcb.fRtsControl = RTS_CONTROL_ENABLE; + } + + if (bIsSuccess) { + /** ʹDCBô״̬ */ + bIsSuccess = SetCommState(hComm, &dcb); + if (!bIsSuccess) { + cout << "SetCommState error!" << endl; + } + } + + /** մڻ */ + PurgeComm(hComm, PURGE_RXCLEAR | PURGE_TXCLEAR | PURGE_RXABORT | PURGE_TXABORT); + + return bIsSuccess; +} + +UINT Serial::GetBytesInCOM() const { + DWORD dwError = 0; /** */ + COMSTAT comstat; /** COMSTATṹ,¼ͨ豸״̬Ϣ */ + memset(&comstat, 0, sizeof(COMSTAT)); + + UINT BytesInQue = 0; + /** ڵReadFileWriteFile֮ǰ,ͨǰĴ־ */ + if (ClearCommError(hComm, &dwError, &comstat)) { + BytesInQue = comstat.cbInQue; /** ȡ뻺еֽ */ + } + + return BytesInQue; +} + +bool Serial::WriteData(const unsigned char* pData, unsigned int length) { + if (hComm == INVALID_HANDLE_VALUE) { + ErrorHandler(); + return false; + } + + /** 򻺳дָ */ + BOOL bResult = TRUE; + DWORD BytesToSend = 0; + bResult = WriteFile(hComm, pData, length, &BytesToSend, NULL); + if (!bResult) { + DWORD dwError = GetLastError(); + /** մڻ */ + PurgeComm(hComm, PURGE_RXCLEAR | PURGE_RXABORT); + ErrorHandler(); + return false; + } + return true; +} + +bool Serial::ReadData(unsigned char *buffer, unsigned int length) { + if (hComm == INVALID_HANDLE_VALUE) { + ErrorHandler(); + return false; + } + + /** ӻȡlengthֽڵ */ + BOOL bResult = TRUE; + DWORD totalRead = 0, onceRead = 0; + while (totalRead < length) { + bResult = ReadFile(hComm, buffer, length-totalRead, &onceRead, NULL); + totalRead += onceRead; + if ((!bResult)) { + /** ȡ,Ըݸôԭ */ + DWORD dwError = GetLastError(); + + /** մڻ */ + PurgeComm(hComm, PURGE_RXCLEAR | PURGE_RXABORT); + ErrorHandler(); + return false; + } + } + return bResult; +} diff --git a/others/src/uart/uart.cpp b/others/src/uart/uart.cpp deleted file mode 100644 index e9ea4f7..0000000 --- a/others/src/uart/uart.cpp +++ /dev/null @@ -1,183 +0,0 @@ -// -// Created by xixiliadorabarry on 1/24/19. -// - -#include -#include -#include -#include - -using namespace std; - -GMAngle_t aim; - -string get_uart_dev_name(){ - FILE* ls = popen("ls /dev/ttyUSB* --color=never", "r"); - char name[20] = {0}; - fscanf(ls, "%s", name); - return name; -} - -Uart::Uart(){ - if(wait_uart){ - string name; - do{ - name = get_uart_dev_name(); - if(name == ""){ - continue; - } - }while((fd=open(name.data(), O_RDWR)) < 0); - }else{ - string name = get_uart_dev_name(); - if(name == ""){ - cerr<<"open port error"<> 8) & 0xFF; - buff[3] = 0 & 0xFF; - buff[4] = '+'; - buff[5] = (0 >> 8) & 0xFF; - buff[6] = (0 & 0xFF); - buff[7] = 'e'; - - fps = 0; - cur_time = time(nullptr); - -} - -int Uart::set_opt(int fd, int nSpeed, int nBits, char nEvent, int nStop) { - termios newtio{}, oldtio{}; - if (tcgetattr(fd, &oldtio) != 0) { - perror("SetupSerial 1"); - return -1; - } - bzero(&newtio, sizeof(newtio)); - newtio.c_cflag |= CLOCAL | CREAD; - newtio.c_cflag &= ~CSIZE; - - switch (nBits) { - case 7: - newtio.c_cflag |= CS7;break; - case 8: - newtio.c_cflag |= CS8;break; - default:break; - } - - switch (nEvent) { - case 'O': //奇校验 - newtio.c_cflag |= PARENB; - newtio.c_cflag |= PARODD; - newtio.c_iflag |= (INPCK | ISTRIP); - break; - case 'E': //偶校验 - newtio.c_iflag |= (INPCK | ISTRIP); - newtio.c_cflag |= PARENB; - newtio.c_cflag &= ~PARODD; - break; - case 'N': //无校验 - newtio.c_cflag &= ~PARENB; - break; - default:break; - } - - switch (nSpeed) { - case 2400: - cfsetispeed(&newtio, B2400); - cfsetospeed(&newtio, B2400); - break; - case 4800: - cfsetispeed(&newtio, B4800); - cfsetospeed(&newtio, B4800); - break; - case 9600: - cfsetispeed(&newtio, B9600); - cfsetospeed(&newtio, B9600); - break; - case 115200: - cfsetispeed(&newtio, B115200); - cfsetospeed(&newtio, B115200); - break; - default: - cfsetispeed(&newtio, B9600); - cfsetospeed(&newtio, B9600); - break; - } - - if (nStop == 1) { - newtio.c_cflag &= ~CSTOPB; - } else if (nStop == 2) { - newtio.c_cflag |= CSTOPB; - } - - newtio.c_cc[VTIME] = 0; - newtio.c_cc[VMIN] = 0; - tcflush(fd, TCIFLUSH); - if ((tcsetattr(fd, TCSANOW, &newtio)) != 0) { - perror("com set error"); - return -1; - } - printf("set done!\n"); - - return 0; -} - -void Uart::sendTarget(float x, float y, float z) { - static short x_tmp, y_tmp, z_tmp; - - time_t t = time(nullptr); - if(cur_time != t) - { - cur_time = t; - cout<<"fps:"<(x * (32768 - 1) / 100); - y_tmp= static_cast(y * (32768 - 1) / 100); - z_tmp= static_cast(z * (32768 - 1) / 1000); - - buff[0] = 's'; - buff[1] = static_cast((x_tmp >> 8) & 0xFF); - buff[2] = static_cast((x_tmp >> 0) & 0xFF); - buff[3] = static_cast((y_tmp >> 8) & 0xFF); - buff[4] = static_cast((y_tmp >> 0) & 0xFF); - buff[5] = static_cast((z_tmp >> 8) & 0xFF); - buff[6] = static_cast((z_tmp >> 0) & 0xFF); - buff[7] = 'e'; - - int cnt=0; - while((cnt+=write(fd, buff+cnt, 8-cnt))!=-1 && cnt<8); - if(cnt==-1 && wait_uart){ - LOGE("Uart send fail, the uart device may offline! Restart!"); - exit(-1); - } -} - -uint8_t Uart::receive() { - uint8_t data; - while(read(fd, &data, 1) < 1); - return data; -} diff --git a/tools/monitor.bat b/tools/monitor.bat new file mode 100644 index 0000000..e8fa909 --- /dev/null +++ b/tools/monitor.bat @@ -0,0 +1,53 @@ +@echo off + +rem سĽͳ·ɸҪ޸ + +set AppName=run.exe + +set AppArgs= --run-with-camera --wait-uart --show-armor-box + +set AppPath=C:\Users\sjturm\Desktop\AutoAim\build\Release\ + +title ̼ + +cls + +echo. + +echo ̼ؿʼ + +echo. + +rem ѭ + +:startjc + + rem ӽбвָ + + rem Ҳд qprocess %AppName% >nul 鷢󲹳䣩 + + qprocess|findstr /i %AppName% >nul + + rem errorlevelֵ0ʾҵ̣ûвҵ + + if %errorlevel%==0 ( + + echo ^>%date:~0,10% %time:~0,8% С + + )else ( + + echo ^>%date:~0,10% %time:~0,8% ûзֳ + + echo ^>%date:~0,10% %time:~0,8% + + start %AppPath%%AppName%%AppArgs% 2>nul && echo ^>%date:~0,10% %time:~0,8% ɹ + + ) + + rem pingʵʱ + + ping -n 2 -w 1000 1.1.1.1>nul + + goto startjc + +echo on \ No newline at end of file