diff --git a/externals/UartDemo.cpp b/externals/UartDemo.cpp new file mode 100644 index 00000000..5a4cbd5c --- /dev/null +++ b/externals/UartDemo.cpp @@ -0,0 +1,439 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +# define BARE_RUN +# ifndef BARE_RUN +#include +#include +#include +# endif +#define PI 3.14159265 + +static int ret; +static int fd; +float a[3],w[3],Angle[3],h[3]; + +struct CurrentPose +{ + float x; + float y; + float theta; // In rads +}; +bool init = false; +float theta = 0; + +CurrentPose currentpose = {0,0,0}; + +#define BAUD 9600 +// open device based on device name + +int uart_open(int fd,const char *pathname) +{ + fd = open(pathname, O_RDWR|O_NOCTTY); + if (-1 == fd) + { + perror("Can't Open Serial Port"); + return(-1); + } + else + printf("open %s success!\n",pathname); + /*测试是否为终端设备*/ + if(isatty(STDIN_FILENO)==0) + printf("standard input is not a terminal device\n"); + else + printf("isatty success!\n"); + return fd; +} + +int uart_set(int fd,int nSpeed, int nBits, char nEvent, int nStop) +{ + struct termios newtio,oldtio; + /*保存测试现有串口参数设置,在这里如果串口号等出错,会有相关的出错信息*/ + if ( tcgetattr( fd,&oldtio) != 0) { + perror("SetupSerial 1"); + printf("tcgetattr( fd,&oldtio) -> %d\n",tcgetattr( fd,&oldtio)); + 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; + + } + + /*设置奇偶校验位*/ + + switch( nEvent ) + + { + + case 'o': + + case 'O': //奇数 + + newtio.c_cflag |= PARENB; + + newtio.c_cflag |= PARODD; + + newtio.c_iflag |= (INPCK | ISTRIP); + + break; + + case 'e': + + case 'E': //偶数 + + newtio.c_iflag |= (INPCK | ISTRIP); + + newtio.c_cflag |= PARENB; + + newtio.c_cflag &= ~PARODD; + + break; + + case 'n': + + 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; + + case 460800: + + cfsetispeed(&newtio, B460800); + + cfsetospeed(&newtio, B460800); + + 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; +} + +int uart_close(int fd) +{ + assert(fd); + close(fd); + + /*可以在这里做些清理工作*/ + + return 0; +} + +int send_data(int fd, char *send_buffer,int length) +{ + length=write(fd,send_buffer,length*sizeof(unsigned char)); + return length; + +} + +int recv_data(int fd, char* recv_buffer,int length) +{ + length=read(fd,recv_buffer,length); + return length; +} +# ifndef BARE_RUN +void pose_recv_callback(const geometry_msgs::Pose2D::ConstPtr& msg) +{ + // How to unpack data + currentpose.x = msg->x; + currentpose.y = msg->y; +} +#endif +float angle_from_h(float h[3]) +{ + return atan2(h[1],h[0]); +} + +float ring(float i) // Calc in Rads +{ + i += PI/2; + float num = fmod(PI+fmod(i,PI), PI); + return num - PI/2; +} + +// Assume we need to transfer to python version here contains data we need to transfer +// 一次一个字节的存储解释数据 +void ParseData(char chr) +{ + static char chrBuf[100]; + static unsigned char chrCnt=0; + signed short sData[4]; + unsigned char i; + time_t now; + chrBuf[chrCnt++]=chr; + if (chrCnt<11) return; + + if ((chrBuf[0]!=0x55)||((chrBuf[1]&0x50)!=0x50)) {printf("Error:%x %x\r\n",chrBuf[0],chrBuf[1]);memcpy(&chrBuf[0],&chrBuf[1],10);chrCnt--;return;} + memcpy(&sData[0],&chrBuf[2],8); + switch(chrBuf[1]) + { + case 0x51: + for (i=0;i<3;i++) a[i] = (float)sData[i]/32768.0*16.0; + time(&now); + printf("\r\nT:%s a:%6.3f %6.3f %6.3f ",asctime(localtime(&now)),a[0],a[1],a[2]); + + break; + case 0x52: + for (i=0;i<3;i++) + w[i] = (float)sData[i]/32768.0*2000.0; + printf("w:%7.3f %7.3f %7.3f ",w[0],w[1],w[2]); + + break; + case 0x53: + for (i=0;i<3;i++) + Angle[i] = (float)sData[i]/32768.0*180.0; + printf("A:%7.3f %7.3f %7.3f ",Angle[0],Angle[1],Angle[2]); + break; + case 0x54: // Here is desired data magnetic field data + for (i=0;i<3;i++) + h[i] = (float)sData[i]/32768.0*1.0; + printf("h:%4.0f %4.0f %4.0f ",h[1],h[1],h[2]); // xyz?? + // Add a process function + theta = angle_from_h(h); + + break; + } + chrCnt=0; + +} +#ifndef BARE_RUN +void TaskLoop(float theta,ros::Publisher pose_pub) +{ + static bool oninit = true; + static float yaw_offset = 0; + static int init_counter = 0; + static geometry_msgs::Pose2D forwardmsg; + static std::chrono::high_resolution_clock::time_point last_time = std::chrono::high_resolution_clock::now(); + if(oninit) + { + init_counter ++; + if(init_counter>1) + yaw_offset += theta/init_counter + yaw_offset/(init_counter-1); + else if(init_counter==1) + yaw_offset = theta; + if(init_counter>2000) // Supposingly 2s + { + oninit = false; + init = true; + } + } + else + { + theta = ring(theta - yaw_offset); + currentpose.theta = theta; + forwardmsg.x = currentpose.x; + forwardmsg.y = currentpose.y; + forwardmsg.theta = currentpose.theta; + // Publish message + if(std::chrono::duration_cast>(std::chrono::high_resolution_clock::now() - last_time).count() > 0.025) // May be 40fps + { + last_time = std::chrono::high_resolution_clock::now(); + pose_pub.publish(forwardmsg); + } + } +} +#else +void TaskLoop(float theta) +{ + static bool oninit = true; + static float yaw_offset = 0; + static int init_counter = 0; + static std::chrono::high_resolution_clock::time_point last_time = std::chrono::high_resolution_clock::now(); + if(oninit) + { + init_counter ++; + if(init_counter>1) + yaw_offset += theta/init_counter + yaw_offset/(init_counter-1); + else if(init_counter==1) + yaw_offset = theta; + if(init_counter>2000) // Supposingly 2s + { + oninit = false; + init = true; + } + } + else + { + theta = ring(theta - yaw_offset); + currentpose.theta = theta; + if(std::chrono::duration_cast>(std::chrono::high_resolution_clock::now() - last_time).count() > 0.1) // May be 40fps + { + last_time = std::chrono::high_resolution_clock::now(); + std::cout<<"Theta Angle is: "<("uwb",1000); + ros::Subscriber pose_sub = n.subscribe ("robot_pose",1000,pose_recv_callback); + #endif + char r_buf[1024]; + bzero(r_buf,1024); + + fd = uart_open(fd,"/dev/ttyUSB0");/*串口号/dev/ttySn,USB口号/dev/ttyUSBn*/ + if(fd == -1) + { + fprintf(stderr,"uart_open error\n"); + exit(EXIT_FAILURE); + } + + if(uart_set(fd,BAUD,8,'N',1) == -1) + { + fprintf(stderr,"uart set failed!\n"); + exit(EXIT_FAILURE); + } + + FILE *fp; + fp = fopen("Record.txt","w"); + while(1) + { + ret = recv_data(fd,r_buf,44); + if(ret == -1) + { + fprintf(stderr,"uart read failed!\n"); + exit(EXIT_FAILURE); + } + for (int i=0;i u void Chassis::ChassisSpeedCtrlCallback(const geometry_msgs::Twist::ConstPtr &vel){ roborts_sdk::cmd_chassis_speed chassis_speed; - chassis_speed.vx = vel->linear.x*1000; - chassis_speed.vy = vel->linear.y*1000; - chassis_speed.vw = vel->angular.z * 1800.0 / M_PI; + //int chassis_speed_ratio = 1; // Adjust chassis's speed limit + chassis_speed.vx = vel->linear.x*1000; //* chassis_speed_ratio; + chassis_speed.vy = vel->linear.y*1000; //* chassis_speed_ratio; + chassis_speed.vw = vel->angular.z * 1800.0 / M_PI; //* chassis_speed_ratio; chassis_speed.rotate_x_offset = 0; chassis_speed.rotate_y_offset = 0; chassis_speed_pub_->Publish(chassis_speed); @@ -137,8 +138,8 @@ void Chassis::ChassisSpeedCtrlCallback(const geometry_msgs::Twist::ConstPtr &vel void Chassis::ChassisSpeedAccCtrlCallback(const roborts_msgs::TwistAccel::ConstPtr &vel_acc){ roborts_sdk::cmd_chassis_spd_acc chassis_spd_acc; - chassis_spd_acc.vx = vel_acc->twist.linear.x*1000; - chassis_spd_acc.vy = vel_acc->twist.linear.y*1000; + chassis_spd_acc.vx = vel_acc->twist.linear.x*500; + chassis_spd_acc.vy = vel_acc->twist.linear.y*500; chassis_spd_acc.vw = vel_acc->twist.angular.z * 1800.0 / M_PI; chassis_spd_acc.ax = vel_acc->accel.linear.x*1000; chassis_spd_acc.ay = vel_acc->accel.linear.y*1000; diff --git a/roborts_bringup/launch/mapping_stage.launch b/roborts_bringup/launch/mapping_stage.launch index 4704cbf2..d4801f91 100755 --- a/roborts_bringup/launch/mapping_stage.launch +++ b/roborts_bringup/launch/mapping_stage.launch @@ -1,7 +1,7 @@ - + diff --git a/roborts_bringup/launch/roborts.launch b/roborts_bringup/launch/roborts.launch index 81d8c3d4..72b6c796 100755 --- a/roborts_bringup/launch/roborts.launch +++ b/roborts_bringup/launch/roborts.launch @@ -1,6 +1,6 @@ - + @@ -16,8 +16,7 @@ - - + @@ -32,6 +31,7 @@ - + + diff --git a/roborts_bringup/launch/roborts_stage.launch b/roborts_bringup/launch/roborts_stage.launch index 1241f3c2..b163e44c 100755 --- a/roborts_bringup/launch/roborts_stage.launch +++ b/roborts_bringup/launch/roborts_stage.launch @@ -1,5 +1,5 @@ - + diff --git a/roborts_bringup/launch/static_tf.launch b/roborts_bringup/launch/static_tf.launch index 4cb3a99e..4ef75ba5 100644 --- a/roborts_bringup/launch/static_tf.launch +++ b/roborts_bringup/launch/static_tf.launch @@ -2,9 +2,11 @@ + args="0.0 0.0 0.0 0.0 0.0 0.0 base_link base_laser_link" /> - - \ No newline at end of file + + + diff --git a/roborts_bringup/maps/icra2020.pgm b/roborts_bringup/maps/icra2020.pgm new file mode 100644 index 00000000..ead5850b Binary files /dev/null and b/roborts_bringup/maps/icra2020.pgm differ diff --git a/roborts_bringup/maps/icra2020.yaml b/roborts_bringup/maps/icra2020.yaml new file mode 100755 index 00000000..b24aa0d5 --- /dev/null +++ b/roborts_bringup/maps/icra2020.yaml @@ -0,0 +1,7 @@ +image: icra2020.pgm +resolution: 0.04 +origin: [0, 0, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/roborts_bringup/worlds/icra2020.world b/roborts_bringup/worlds/icra2020.world new file mode 100755 index 00000000..daea8a78 --- /dev/null +++ b/roborts_bringup/worlds/icra2020.world @@ -0,0 +1,87 @@ +define block model +( + size [0.4 0.4 1.2] + ranger_return 1 +) + +define frontcamera camera +( + size [ 0.050 0.050 0.0500 ] + range [ 0.301 8.0 ] + resolution [ 640 480 ] + fov [ 120 40 ] + pantilt [ 0 0 ] + alwayson 1 +) + +define rplidar ranger +( + sensor( + range_max 8.0 + fov 270 + samples 270 + ) + # generic model properties + color "black" + size [ 0.050 0.050 0.100 ] +) + +define rmcar position +( + size [0.6 0.45 0.460] + origin [0 0 0 0] + gui_nose 1 + drive "omni" + # frontcamera(pose [ 0 0 0 0 ]) + rplidar(pose [ 0 0 0 0 ]) + odom_error [0.03 0.03 0.00 0.05] + # [ xmin xmax ymin ymax zmin zmax amin amax ] + velocity_bounds [-2 2 -2 2 -2 2 -90 90 ] + acceleration_bounds [-2 2 -2 2 -2 2 -90 90] + ranger_return 1 +) + +define floorplan model +( + # sombre, sensible, artistic + color "gray30" + + # most maps will need a bounding box + boundary 0 + + gui_nose 0 + gui_grid 0 + + gui_outline 0 + gripper_return 0 + fiducial_return 0 + ranger_return 1 +) + +# set the resolution of the underlying raytrace model in meters +resolution 0.01 + +interval_sim 50#83 # simulation timestep in milliseconds +interval_real 50#83 + +window +( + size [ 745.000 448.000 ] + rotate [ 0 0 ] + scale 29 +) + +# load an environment bitmap +floorplan +( + name "RoboMaster Map" + bitmap "../maps/icra2020.pgm" + size [8.2 4.5 0.500] + pose [4.1 2.25 0 0 ] + #pose [0 0 0 0 ] +) + +# throw in a robot + rmcar(pose [ 1 1 0 3.14 ] name "rmcar0" color "blue" ) +# throw in a block for test + block(pose [ 7.79 3.45 0 0.3 ] color "red" ) diff --git a/roborts_camera/CMakeLists.txt b/roborts_camera/CMakeLists.txt index f885faac..5534ac6a 100755 --- a/roborts_camera/CMakeLists.txt +++ b/roborts_camera/CMakeLists.txt @@ -22,6 +22,7 @@ catkin_package( ) add_subdirectory(uvc) +add_subdirectory(mvc) #camera parameter file(GLOB CameraParamProtoFiles "${CMAKE_CURRENT_SOURCE_DIR}/proto/camera_param.proto") @@ -59,9 +60,11 @@ add_executable(${PROJECT_NAME}_node target_link_libraries(${PROJECT_NAME}_node PRIVATE driver::uvc_driver + driver::mvc_driver roborts_camera_param ${catkin_LIBRARIES} ${OpenCV_LIBRARIES} + libMVSDK.so ) target_include_directories(${PROJECT_NAME}_node @@ -78,10 +81,13 @@ add_executable(image_capture_test target_link_libraries(image_capture_test PRIVATE + PUBLIC driver::uvc_driver + driver::mvc_driver roborts_camera_param ${catkin_LIBRARIES} ${OpenCV_LIBRARIES} + libMVSDK.so ) target_include_directories(image_capture_test diff --git a/roborts_camera/camera_node.h b/roborts_camera/camera_node.h index 3cdcca4a..ce6bc9de 100755 --- a/roborts_camera/camera_node.h +++ b/roborts_camera/camera_node.h @@ -27,6 +27,7 @@ #include #include "uvc/uvc_driver.h" +#include "mvc/mvc_driver.h" #include "camera_param.h" #include "camera_base.h" diff --git a/roborts_camera/camera_param.cpp b/roborts_camera/camera_param.cpp index 88a757c5..a55e4fce 100755 --- a/roborts_camera/camera_param.cpp +++ b/roborts_camera/camera_param.cpp @@ -62,7 +62,10 @@ void CameraParam::LoadCameraParam() { //constrast cameras_param_[index].contrast = camera_info.camera(index).contrast(); - + // Gamma value + cameras_param_[index].gamma = camera_info.camera(index).gamma(); + // Gain value + cameras_param_[index].gain = camera_info.camera(index).gain(); //camera matrix int camera_m_size = camera_info.camera(index).camera_matrix().data().size(); double camera_m[camera_m_size]; diff --git a/roborts_camera/camera_param.h b/roborts_camera/camera_param.h index 1e8dd6bc..2dd16c25 100755 --- a/roborts_camera/camera_param.h +++ b/roborts_camera/camera_param.h @@ -56,13 +56,15 @@ struct CameraInfo { //! exposure value unsigned int exposure_value; //! exposure time - unsigned int exposure_time; + double exposure_time; //! auto white balance bool auto_white_balance; //! auto gain bool auto_gain; //! contrast unsigned int contrast; + unsigned int gamma; + unsigned int gain; //! camera information in form of ROS sensor_msgs sensor_msgs::CameraInfoPtr ros_camera_info; diff --git a/roborts_camera/config/camera_param.prototxt b/roborts_camera/config/camera_param.prototxt index 9df65121..3f263893 100755 --- a/roborts_camera/config/camera_param.prototxt +++ b/roborts_camera/config/camera_param.prototxt @@ -1,41 +1,44 @@ camera: { camera_name: "back_camera" - camera_type: "uvc" - camera_path: "/dev/video0" + camera_type: "mvc" + camera_path: "/dev/video3" camera_matrix { - data: 839.923052 + data: 737.13167516 data: 0.0 - data: 340.780730 + data: 394.02392383 data: 0.0 - data: 837.671081 - data: 261.766523 + data: 753.8582612 + data: 236.24307876 data: 0.0 data: 0.0 data: 1.0 } camera_distortion { - data: 0.082613 - data: 0.043275 - data: 0.002486 - data: -0.000823 - data: 0.0 + data: 0.26802427 + data: -0.98025777 + data: -0.00674122 + data: 0.01944969 + data: 1.995706 } resolution { width: 640 - height: 360 + height: 480 width_offset: 0 height_offset: 0 } - fps: 100 - auto_exposure: 1 + fps: 110 + auto_exposure: 0 exposure_value: 70 - exposure_time: 10 - auto_white_balance: 1 + exposure_time: 900 + auto_white_balance: 0 + gamma: 65 + contrast: 44 auto_gain: 0 + gain: 48 } diff --git a/roborts_camera/libMVSDK.so b/roborts_camera/libMVSDK.so new file mode 100644 index 00000000..e5fd46eb Binary files /dev/null and b/roborts_camera/libMVSDK.so differ diff --git a/roborts_camera/mvc/CMakeLists.txt b/roborts_camera/mvc/CMakeLists.txt new file mode 100644 index 00000000..d3cf5546 --- /dev/null +++ b/roborts_camera/mvc/CMakeLists.txt @@ -0,0 +1,21 @@ +project(mvc_driver) + +#mvc_driver +add_library(mvc_driver + SHARED + mvc_driver.cpp +) + +target_link_libraries(mvc_driver + PRIVATE + ${catkin_LIBRARIES} + ${OpenCV_LIBRARIES} +) + +target_include_directories(mvc_driver + PRIVATE + ${catkin_INCLUDE_DIRS} + ${OpenCV_INCLUDE_DIRECTORIES} +) + +add_library(driver::mvc_driver ALIAS mvc_driver) diff --git a/roborts_camera/mvc/Camera/Configs/MV-UB31-Group0.config b/roborts_camera/mvc/Camera/Configs/MV-UB31-Group0.config new file mode 100644 index 00000000..4b963a35 --- /dev/null +++ b/roborts_camera/mvc/Camera/Configs/MV-UB31-Group0.config @@ -0,0 +1,181 @@ +create_time = "2020-03-25 15:11:00"; +internal_id = "E7FCFFE8999B"; +resolution : +{ + image_size : + { + iIndex = 1; + acDescription = "640X480"; + 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 = 0; + 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 = true; + show_ae_window = false; + ae_window_height = 0; + ae_window_width = 0; + ae_window_voff = 0; + ae_window_hoff = 0; + analog_gain = 48; + exp_time = 996.3570468565992542; + ae_target = 120; + ae_enable = false; + user_exposure_time = 996.3570468565992542; + 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; + frame_rate = 0; + 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 = 2; +}; +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 = 65; + contrast = 44; + black_level = 0; + white_level = 256; +}; +isp_shape : +{ + noise_reduce = false; + vflip = false; + hflip = false; + hd_flip_h = false; + hd_flip_v = 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_buffered_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; + rotary_enc_dir = 0; + rotary_enc_mul = 1; + rotary_enc_div = 1; +}; +wdr : +{ + awdr_enable = false; +}; +io : +{ + in0 : + { + value = 1; + mode = 0; + format = -1; + }; + out0 : + { + value = 1; + mode = 1; + format = -1; + }; + out1 : + { + value = 1; + mode = 3; + format = -1; + }; +}; diff --git a/roborts_camera/mvc/Camera/Data/020060120099.mvdat b/roborts_camera/mvc/Camera/Data/020060120099.mvdat new file mode 100644 index 00000000..3021d9f8 Binary files /dev/null and b/roborts_camera/mvc/Camera/Data/020060120099.mvdat differ diff --git a/roborts_camera/mvc/CameraApi.h b/roborts_camera/mvc/CameraApi.h new file mode 100644 index 00000000..9770c1da --- /dev/null +++ b/roborts_camera/mvc/CameraApi.h @@ -0,0 +1,4079 @@ +#ifndef _MVCAMAPI_H_ +#define _MVCAMAPI_H_ + +#define MVSDK_API + +#ifdef __cplusplus + extern "C" { + #endif + + +#include "CameraDefine.h" +#include "CameraStatus.h" + + + +/******************************************************/ +// 函数名 : CameraSdkInit +// 功能描述 : 相机SDK初始化,在调用任何SDK其他接口前,必须 +// 先调用该接口进行初始化。该函数在整个进程运行 +// 期间只需要调用一次。 +// 参数 : iLanguageSel 用于选择SDK内部提示信息和界面的语种, +// 0:表示英文,1:表示中文。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSdkInit(int iLanguageSel); + +/******************************************************/ +// 函数名 : CameraSetDataDirectory +// 功能描述 : 设置相机数据文件的存储目录(.config .mvdat等) +// 需要在CameraInit打开相机前设置好 +// 默认目录为当前目录 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetDataDirectory(char const* dirname); + +/******************************************************/ +// 函数名 : CameraUSBDeviceInit +// 功能描述 : (已废弃,无需调用) +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraUSBDeviceInit(); + +/******************************************************/ +// 函数名 : CameraUSBDeviceUninit +// 功能描述 : (已废弃,无需调用) +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraUSBDeviceUninit(); + + +/******************************************************/ +// 函数名 : CameraEnumerateDevice +// 功能描述 : 枚举设备,并建立设备列表。在调用CameraInit +// 之前,必须调用该函数来获得设备的信息。 +// 参数 : pCameraList 设备列表数组指针。 +// piNums 设备的个数指针,调用时传入pCameraList +// 数组的元素个数,函数返回时,保存实际找到的设备个数。 +// 注意,piNums指向的值必须初始化,且不超过pCameraList数组元素个数, +// 否则有可能造成内存溢出。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraEnumerateDevice( + tSdkCameraDevInfo* pCameraList, + INT* piNums +); + +/******************************************************/ +// 函数名 : CameraIdleStateDevice +// 功能描述 : 当前系统有未使用的相机信息。 +// 参数 : pCameraList 设备列表数组指针。 +// piNums 设备的个数指针,调用时传入pCameraList +// 数组的元素个数,函数返回时,保存实际找到的设备个数。 +// 注意,piNums指向的值必须初始化,且不超过pCameraList数组元素个数, +// 否则有可能造成内存溢出。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraIdleStateDevice( + tSdkCameraDevInfo* pCameraList, + INT* piNums +); + + +/******************************************************/ +// 函数名 : CameraEnumerateDeviceEx +// 功能描述 : 枚举设备,并建立设备列表。在调用CameraInitEx +// 之前,必须调用该函数枚举设备。 +// 参数 : +// 返回值 : 返回设备个数,0表示无。 +/******************************************************/ +MVSDK_API INT CameraEnumerateDeviceEx( +); + + +/******************************************************/ +// 函数名 : CameraIsOpened +// 功能描述 : 检测设备是否已经被其他应用程序打开。在调用CameraInit +// 之前,可以使用该函数进行检测,如果已经被打开,调用 +// CameraInit会返回设备已经被打开的错误码。 +// 参数 : pCameraList 设备的枚举信息结构体指针,由CameraEnumerateDevice获得。 +// pOpened 设备的状态指针,返回设备是否被打开的状态,TRUE为打开,FALSE为空闲。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraIsOpened( + tSdkCameraDevInfo* pCameraList, + BOOL* pOpened +); + + +/******************************************************/ +// 函数名 : CameraInit +// 功能描述 : 相机初始化。初始化成功后,才能调用任何其他 +// 相机相关的操作接口。 +// 参数 : pCameraInfo 该相机的设备描述信息,由CameraEnumerateDevice +// 函数获得。 +// iParamLoadMode 相机初始化时使用的参数加载方式。-1表示使用上次退出时的参数加载方式。 +// emTeam 初始化时使用的参数组。-1表示加载上次退出时的参数组。 +// pCameraHandle 相机的句柄指针,初始化成功后,该指针 +// 返回该相机的有效句柄,在调用其他相机 +// 相关的操作接口时,都需要传入该句柄,主要 +// 用于多相机之间的区分。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraInit( + tSdkCameraDevInfo* pCameraInfo, + int emParamLoadMode, + int emTeam, + CameraHandle* pCameraHandle +); + +/******************************************************/ +// 函数名 : CameraInitEx +// 功能描述 : 相机初始化。初始化成功后,才能调用任何其他 +// 相机相关的操作接口。 +// 参数 : iDeviceIndex 相机的索引号,CameraEnumerateDeviceEx返回相机个数。 +// iParamLoadMode 相机初始化时使用的参数加载方式。-1表示使用上次退出时的参数加载方式。 +// emTeam 初始化时使用的参数组。-1表示加载上次退出时的参数组。 +// pCameraHandle 相机的句柄指针,初始化成功后,该指针 +// 返回该相机的有效句柄,在调用其他相机 +// 相关的操作接口时,都需要传入该句柄,主要 +// 用于多相机之间的区分。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraInitEx( + int iDeviceIndex, + int iParamLoadMode, + int emTeam, + CameraHandle* pCameraHandle +); + +/// @ingroup API_OPEN +/// \~chinese +/// \brief 相机初始化。初始化成功后,才能调用其他相机相关的操作接口。 +/// \param [in] CameraName 相机昵称。@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 CameraInitEx2( + char* CameraName, + CameraHandle *pCameraHandle +); + +/******************************************************/ +// 函数名 : CameraSetCallbackFunction +// 功能描述 : 设置图像捕获的回调函数。当捕获到新的图像数据帧时, +// pCallBack所指向的回调函数就会被调用。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pCallBack 回调函数指针。 +// pContext 回调函数的附加参数,在回调函数被调用时 +// 该附加参数会被传入,可以为NULL。多用于 +// 多个相机时携带附加信息。 +// pCallbackOld 用于保存当前的回调函数。可以为NULL。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetCallbackFunction( + CameraHandle hCamera, + CAMERA_SNAP_PROC pCallBack, + PVOID pContext, + CAMERA_SNAP_PROC* pCallbackOld +); + +/******************************************************/ +// 函数名 : CameraUnInit +// 功能描述 : 相机反初始化。释放资源。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraUnInit( + CameraHandle hCamera +); + +/******************************************************/ +// 函数名 : CameraGetInformation +// 功能描述 : 获得相机的描述信息 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pbuffer 指向相机描述信息指针的指针。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetInformation( + CameraHandle hCamera, + char** pbuffer +); + +/******************************************************/ +// 函数名 : CameraImageProcess +// 功能描述 : 将获得的相机原始输出图像数据进行处理,叠加饱和度、 +// 颜色增益和校正、降噪等处理效果,最后得到RGB888 +// 格式的图像数据。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pbyIn 输入图像数据的缓冲区地址,不能为NULL。 +// pbyOut 处理后图像输出的缓冲区地址,不能为NULL。 +// pFrInfo 输入图像的帧头信息,处理完成后,帧头信息 +// 中的图像格式uiMediaType会随之改变。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus 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 +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus 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 +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraDisplayInit( + CameraHandle hCamera, + HWND hWndDisplay +); + +/******************************************************/ +// 函数名 : CameraDisplayRGB24 +// 功能描述 : 显示图像。必须调用过CameraDisplayInit进行 +// 初始化才能调用本函数。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pbyRGB24 图像的数据缓冲区,RGB888格式。 +// pFrInfo 图像的帧头信息。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus 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 +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetDisplayMode( + CameraHandle hCamera, + INT iMode +); + +/******************************************************/ +// 函数名 : CameraSetDisplayOffset +// 功能描述 : 设置显示的起始偏移值。仅当显示模式为DISPLAYMODE_REAL +// 时有效。例如显示控件的大小为320X240,而图像的 +// 的尺寸为640X480,那么当iOffsetX = 160,iOffsetY = 120时 +// 显示的区域就是图像的居中320X240的位置。必须调用过 +// CameraDisplayInit进行初始化才能调用本函数。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iOffsetX 偏移的X坐标。 +// iOffsetY 偏移的Y坐标。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetDisplayOffset( + CameraHandle hCamera, + int iOffsetX, + int iOffsetY +); + +/******************************************************/ +// 函数名 : CameraSetDisplaySize +// 功能描述 : 设置显示控件的尺寸。必须调用过 +// CameraDisplayInit进行初始化才能调用本函数。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iWidth 宽度 +// iHeight 高度 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetDisplaySize( + CameraHandle hCamera, + INT iWidth, + INT iHeight +); + +/******************************************************/ +// 函数名 : CameraGetImageBuffer +// 功能描述 : 获得一帧图像数据。为了提高效率,SDK在图像抓取时采用了零拷贝机制, +// CameraGetImageBuffer实际获得是内核中的一个缓冲区地址, +// 该函数成功调用后,必须调用CameraReleaseImageBuffer释放由 +// CameraGetImageBuffer得到的缓冲区,以便让内核继续使用 +// 该缓冲区。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pFrameInfo 图像的帧头信息指针。 +// pbyBuffer 指向图像的数据的缓冲区指针。由于 +// 采用了零拷贝机制来提高效率,因此 +// 这里使用了一个指向指针的指针。 +// UINT wTimes 抓取图像的超时时间。单位毫秒。在 +// wTimes时间内还未获得图像,则该函数 +// 会返回超时信息。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetImageBuffer( + CameraHandle hCamera, + tSdkFrameHead* pFrameInfo, + BYTE** pbyBuffer, + UINT wTimes +); + +/******************************************************/ +// 函数名 : CameraGetImageBufferEx +// 功能描述 : 获得一帧图像数据。该接口获得的图像是经过处理后的RGB格式。该函数调用后, +// 不需要调用 CameraReleaseImageBuffer 释放,也不要调用free之类的函数释放 +// 来释放该函数返回的图像数据缓冲区。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piWidth 整形指针,返回图像的宽度 +// piHeight 整形指针,返回图像的高度 +// UINT wTimes 抓取图像的超时时间。单位毫秒。在 +// wTimes时间内还未获得图像,则该函数 +// 会返回超时信息。 +// 返回值 : 成功时,返回RGB数据缓冲区的首地址; +// 否则返回0。 +/******************************************************/ +MVSDK_API unsigned char* 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 +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSnapToBuffer( + CameraHandle hCamera, + tSdkFrameHead* pFrameInfo, + BYTE** pbyBuffer, + UINT uWaitTimeMs +); + +/******************************************************/ +// 函数名 : CameraReleaseImageBuffer +// 功能描述 : 释放由CameraGetImageBuffer获得的缓冲区。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pbyBuffer 由CameraGetImageBuffer获得的缓冲区地址。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraReleaseImageBuffer( + CameraHandle hCamera, + BYTE* pbyBuffer +); + +/******************************************************/ +// 函数名 : CameraPlay +// 功能描述 : 让SDK进入工作模式,开始接收来自相机发送的图像 +// 数据。如果当前相机是触发模式,则需要接收到 +// 触发帧以后才会更新图像。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraPlay( + CameraHandle hCamera +); + +/******************************************************/ +// 函数名 : CameraPause +// 功能描述 : 让SDK进入暂停模式,不接收来自相机的图像数据, +// 同时也会发送命令让相机暂停输出,释放传输带宽。 +// 暂停模式下,可以对相机的参数进行配置,并立即生效。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraPause( + CameraHandle hCamera +); + +/******************************************************/ +// 函数名 : CameraStop +// 功能描述 : 让SDK进入停止状态,一般是反初始化时调用该函数, +// 该函数被调用,不能再对相机的参数进行配置。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraStop( + CameraHandle hCamera +); + +/******************************************************/ +// 函数名 : CameraInitRecord +// 功能描述 : 初始化一次录像。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iFormat 录像的格式,当前只支持不压缩和MSCV两种方式。 +// 0:不压缩;1:MSCV方式压缩。 +// pcSavePath 录像文件保存的路径。 +// b2GLimit 如果为TRUE,则文件大于2G时自动分割。 +// dwQuality 录像的质量因子,越大,则质量越好。范围1到100. +// iFrameRate 录像的帧率。建议设定的比实际采集帧率大, +// 这样就不会漏帧。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraInitRecord( + CameraHandle hCamera, + int iFormat, + char* pcSavePath, + BOOL b2GLimit, + DWORD dwQuality, + int iFrameRate +); + +/******************************************************/ +// 函数名 : CameraStopRecord +// 功能描述 : 结束本次录像。当CameraInitRecord后,可以通过该函数 +// 来结束一次录像,并完成文件保存操作。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraStopRecord( + CameraHandle hCamera +); + +/******************************************************/ +// 函数名 : CameraPushFrame +// 功能描述 : 将一帧数据存入录像流中。必须调用CameraInitRecord +// 才能调用该函数。CameraStopRecord调用后,不能再调用 +// 该函数。由于我们的帧头信息中携带了图像采集的时间戳 +// 信息,因此录像可以精准的时间同步,而不受帧率不稳定 +// 的影响。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pbyImageBuffer 图像的数据缓冲区,必须是RGB格式。 +// pFrInfo 图像的帧头信息。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraPushFrame( + CameraHandle hCamera, + BYTE* pbyImageBuffer, + tSdkFrameHead* pFrInfo +); + +/******************************************************/ +// 函数名 : CameraSaveImage +// 功能描述 : 将图像缓冲区的数据保存成图片文件。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// lpszFileName 图片保存文件完整路径。 +// pbyImageBuffer 图像的数据缓冲区。 +// pFrInfo 图像的帧头信息。 +// byFileType 图像保存的格式。取值范围参见CameraDefine.h +// 中emSdkFileType的类型定义。目前支持 +// BMP、JPG、PNG、RAW四种格式。其中RAW表示 +// 相机输出的原始数据,保存RAW格式文件要求 +// pbyImageBuffer和pFrInfo是由CameraGetImageBuffer +// 获得的数据,而且未经CameraImageProcess转换 +// 成BMP格式;反之,如果要保存成BMP、JPG或者 +// PNG格式,则pbyImageBuffer和pFrInfo是由 +// CameraImageProcess处理后的RGB格式数据。 +// 具体用法可以参考Advanced的例程。 +// byQuality 图像保存的质量因子,仅当保存为JPG格式 +// 时该参数有效,范围1到100。其余格式 +// 可以写成0。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSaveImage( + CameraHandle hCamera, + char* lpszFileName, + BYTE* pbyImageBuffer, + tSdkFrameHead* pFrInfo, + BYTE byFileType, + BYTE byQuality +); + +/******************************************************/ +// 函数名 : CameraGetImageResolution +// 功能描述 : 获得当前预览的分辨率。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// psCurVideoSize 结构体指针,用于返回当前的分辨率。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetImageResolution( + CameraHandle hCamera, + tSdkImageResolution* psCurVideoSize +); + +/******************************************************/ +// 函数名 : CameraSetImageResolution +// 功能描述 : 设置预览的分辨率。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pImageResolution 结构体指针,用于返回当前的分辨率。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetImageResolution( + CameraHandle hCamera, + tSdkImageResolution* pImageResolution +); + +/******************************************************/ +// 函数名 : CameraGetMediaType +// 功能描述 : 获得相机当前输出原始数据的格式索引号。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piMediaType 指针,用于返回当前格式类型的索引号。 +// 由CameraGetCapability获得相机的属性, +// 在tSdkCameraCapbility结构体中的pMediaTypeDesc +// 成员中,以数组的形式保存了相机支持的格式, +// piMediaType所指向的索引号,就是该数组的索引号。 +// pMediaTypeDesc[*piMediaType].iMediaType则表示当前格式的 +// 编码。该编码请参见CameraDefine.h中[图像格式定义]部分。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus 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 +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetMediaType( + CameraHandle hCamera, + INT iMediaType +); + +/******************************************************/ +// 函数名 : CameraSetAeState +// 功能描述 : 设置相机曝光的模式。自动或者手动。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// bAeState TRUE,使能自动曝光;FALSE,停止自动曝光。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetAeState( + CameraHandle hCamera, + BOOL bAeState +); + +/******************************************************/ +// 函数名 : CameraGetAeState +// 功能描述 : 获得相机当前的曝光模式。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pAeState 指针,用于返回自动曝光的使能状态。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetAeState( + CameraHandle hCamera, + BOOL* pAeState +); + +/******************************************************/ +// 函数名 : CameraSetSharpness +// 功能描述 : 设置图像的处理的锐化参数。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iSharpness 锐化参数。范围由CameraGetCapability +// 获得,一般是[0,100],0表示关闭锐化处理。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetSharpness( + CameraHandle hCamera, + int iSharpness +); + +/******************************************************/ +// 函数名 : CameraGetSharpness +// 功能描述 : 获取当前锐化设定值。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piSharpness 指针,返回当前设定的锐化的设定值。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetSharpness( + CameraHandle hCamera, + int* piSharpness +); + +/******************************************************/ +// 函数名 : CameraSetLutMode +// 功能描述 : 设置相机的查表变换模式LUT模式。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// emLutMode LUTMODE_PARAM_GEN 表示由伽马和对比度参数动态生成LUT表。 +// LUTMODE_PRESET 表示使用预设的LUT表。 +// LUTMODE_USER_DEF 表示使用用户自定的LUT表。 +// LUTMODE_PARAM_GEN的定义参考CameraDefine.h中emSdkLutMode类型。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetLutMode( + CameraHandle hCamera, + int emLutMode +); + +/******************************************************/ +// 函数名 : CameraGetLutMode +// 功能描述 : 获得相机的查表变换模式LUT模式。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pemLutMode 指针,返回当前LUT模式。意义与CameraSetLutMode +// 中emLutMode参数相同。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetLutMode( + CameraHandle hCamera, + int* pemLutMode +); + +/******************************************************/ +// 函数名 : CameraSelectLutPreset +// 功能描述 : 选择预设LUT模式下的LUT表。必须先使用CameraSetLutMode +// 将LUT模式设置为预设模式。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iSel 表的索引号。表的个数由CameraGetCapability +// 获得。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSelectLutPreset( + CameraHandle hCamera, + int iSel +); + +/******************************************************/ +// 函数名 : CameraGetLutPresetSel +// 功能描述 : 获得预设LUT模式下的LUT表索引号。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piSel 指针,返回表的索引号。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetLutPresetSel( + CameraHandle hCamera, + int* piSel +); + +/******************************************************/ +// 函数名 : CameraSetCustomLut +// 功能描述 : 设置自定义的LUT表。必须先使用CameraSetLutMode +// 将LUT模式设置为自定义模式。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iChannel 指定要设定的LUT颜色通道,当为LUT_CHANNEL_ALL时, +// 三个通道的LUT将被同时替换。 +// 参考CameraDefine.h中emSdkLutChannel定义。 +// pLut 指针,指向LUT表的地址。LUT表为无符号短整形数组,数组大小为 +// 4096,分别代码颜色通道从0到4096(12bit颜色精度)对应的映射值。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetCustomLut( + CameraHandle hCamera, + int iChannel, + USHORT* pLut +); + +/******************************************************/ +// 函数名 : CameraGetCustomLut +// 功能描述 : 获得当前使用的自定义LUT表。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iChannel 指定要获得的LUT颜色通道。当为LUT_CHANNEL_ALL时, +// 返回红色通道的LUT表。 +// 参考CameraDefine.h中emSdkLutChannel定义。 +// pLut 指针,指向LUT表的地址。LUT表为无符号短整形数组,数组大小为 +// 4096,分别代码颜色通道从0到4096(12bit颜色精度)对应的映射值。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetCustomLut( + CameraHandle hCamera, + int iChannel, + USHORT* pLut +); + +/******************************************************/ +// 函数名 : CameraGetCurrentLut +// 功能描述 : 获得相机当前的LUT表,在任何LUT模式下都可以调用, +// 用来直观的观察LUT曲线的变化。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iChannel 指定要获得的LUT颜色通道。当为LUT_CHANNEL_ALL时, +// 返回红色通道的LUT表。 +// 参考CameraDefine.h中emSdkLutChannel定义。 +// pLut 指针,指向LUT表的地址。LUT表为无符号短整形数组,数组大小为 +// 4096,分别代码颜色通道从0到4096(12bit颜色精度)对应的映射值。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetCurrentLut( + CameraHandle hCamera, + int iChannel, + USHORT* pLut +); + +/******************************************************/ +// 函数名 : CameraSetWbMode +// 功能描述 : 设置相机白平衡模式。分为手动和自动两种方式。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// bAuto TRUE,则表示使能自动模式。 +// FALSE,则表示使用手动模式,通过调用 +// CameraSetOnceWB来进行一次白平衡。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetWbMode( + CameraHandle hCamera, + BOOL bAuto +); + +/******************************************************/ +// 函数名 : CameraGetWbMode +// 功能描述 : 获得当前的白平衡模式。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pbAuto 指针,返回TRUE表示自动模式,FALSE +// 为手动模式。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetWbMode( + CameraHandle hCamera, + BOOL* pbAuto +); + +/******************************************************/ +// 函数名 : CameraSetPresetClrTemp +// 功能描述 : 选择指定预设色温模式 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iSel 预设色温的模式索引号,从0开始 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetPresetClrTemp( + CameraHandle hCamera, + int iSel +); + +/******************************************************/ +// 函数名 : CameraGetPresetClrTemp +// 功能描述 : 获得当前选择的预设色温模式。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piSel 指针,返回选择的预设色温索引号 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetPresetClrTemp( + CameraHandle hCamera, + int* piSel +); + +/******************************************************/ +// 函数名 : CameraSetUserClrTempGain +// 功能描述 : 设置自定义色温模式下的数字增益 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iRgain 红色增益,范围0到400,表示0到4倍 +// iGgain 绿色增益,范围0到400,表示0到4倍 +// iBgain 蓝色增益,范围0到400,表示0到4倍 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetUserClrTempGain( + CameraHandle hCamera, + int iRgain, + int iGgain, + int iBgain +); + + +/******************************************************/ +// 函数名 : CameraGetUserClrTempGain +// 功能描述 : 获得自定义色温模式下的数字增益 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piRgain 指针,返回红色增益,范围0到400,表示0到4倍 +// piGgain 指针,返回绿色增益,范围0到400,表示0到4倍 +// piBgain 指针,返回蓝色增益,范围0到400,表示0到4倍 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetUserClrTempGain( + CameraHandle hCamera, + int* piRgain, + int* piGgain, + int* piBgain +); + +/******************************************************/ +// 函数名 : CameraSetUserClrTempMatrix +// 功能描述 : 设置自定义色温模式下的颜色矩阵 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pMatrix 指向一个float[3][3]数组的首地址 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetUserClrTempMatrix( + CameraHandle hCamera, + float* pMatrix +); + + +/******************************************************/ +// 函数名 : CameraGetUserClrTempMatrix +// 功能描述 : 获得自定义色温模式下的颜色矩阵 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pMatrix 指向一个float[3][3]数组的首地址 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetUserClrTempMatrix( + CameraHandle hCamera, + float* pMatrix +); + +/******************************************************/ +// 函数名 : CameraSetClrTempMode +// 功能描述 : 设置白平衡时使用的色温模式, +// 支持的模式有三种,分别是自动,预设和自定义。 +// 自动模式下,会自动选择合适的色温模式 +// 预设模式下,会使用用户指定的色温模式 +// 自定义模式下,使用用户自定义的色温数字增益和矩阵 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iMode 模式,只能是emSdkClrTmpMode中定义的一种 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetClrTempMode( + CameraHandle hCamera, + int iMode +); + +/******************************************************/ +// 函数名 : CameraGetClrTempMode +// 功能描述 : 获得白平衡时使用的色温模式。参考CameraSetClrTempMode +// 中功能描述部分。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pimode 指针,返回模式选择,参考emSdkClrTmpMode类型定义 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetClrTempMode( + CameraHandle hCamera, + int* pimode +); + + + +/******************************************************/ +// 函数名 : CameraSetOnceWB +// 功能描述 : 在手动白平衡模式下,调用该函数会进行一次白平衡。 +// 生效的时间为接收到下一帧图像数据时。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetOnceWB( + CameraHandle hCamera +); + +/******************************************************/ +// 函数名 : CameraSetOnceBB +// 功能描述 : 执行一次黑平衡操作。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetOnceBB( + CameraHandle hCamera +); + + +/******************************************************/ +// 函数名 : CameraSetAeTarget +// 功能描述 : 设定自动曝光的亮度目标值。设定范围由CameraGetCapability +// 函数获得。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iAeTarget 亮度目标值。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetAeTarget( + CameraHandle hCamera, + int iAeTarget +); + +/******************************************************/ +// 函数名 : CameraGetAeTarget +// 功能描述 : 获得自动曝光的亮度目标值。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// *piAeTarget 指针,返回目标值。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetAeTarget( + CameraHandle hCamera, + int* piAeTarget +); + + +/******************************************************/ +// 函数名 : CameraSetAeExposureRange +// 功能描述 : 设定自动曝光模式的曝光时间调节范围 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// fMinExposureTime 最小曝光时间(微秒) +// fMaxExposureTime 最大曝光时间(微秒) +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetAeExposureRange( + CameraHandle hCamera, + double fMinExposureTime, + double fMaxExposureTime + ); + +/******************************************************/ +// 函数名 : CameraGetAeExposureRange +// 功能描述 : 获得自动曝光模式的曝光时间调节范围 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// fMinExposureTime 最小曝光时间(微秒) +// fMaxExposureTime 最大曝光时间(微秒) +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetAeExposureRange( + CameraHandle hCamera, + double* fMinExposureTime, + double* fMaxExposureTime + ); + +/******************************************************/ +// 函数名 : CameraSetAeAnalogGainRange +// 功能描述 : 设定自动曝光模式的增益调节范围 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iMinAnalogGain 最小增益 +// iMaxAnalogGain 最大增益 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetAeAnalogGainRange( + CameraHandle hCamera, + int iMinAnalogGain, + int iMaxAnalogGain + ); + +/******************************************************/ +// 函数名 : CameraGetAeAnalogGainRange +// 功能描述 : 获得自动曝光模式的增益调节范围 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iMinAnalogGain 最小增益 +// iMaxAnalogGain 最大增益 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetAeAnalogGainRange( + CameraHandle hCamera, + int* iMinAnalogGain, + int* iMaxAnalogGain + ); + + +/******************************************************/ +// 函数名 : CameraSetExposureTime +// 功能描述 : 设置曝光时间。单位为微秒。对于CMOS传感器,其曝光 +// 的单位是按照行来计算的,因此,曝光时间并不能在微秒 +// 级别连续可调。而是会按照整行来取舍。在调用 +// 本函数设定曝光时间后,建议再调用CameraGetExposureTime +// 来获得实际设定的值。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// fExposureTime 曝光时间,单位微秒。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ + +MVSDK_API CameraSdkStatus CameraSetExposureTime( + CameraHandle hCamera, + double fExposureTime +); + +/******************************************************/ +// 函数名 : CameraGetExposureLineTime +// 功能描述 : 获得一行的曝光时间。对于CMOS传感器,其曝光 +// 的单位是按照行来计算的,因此,曝光时间并不能在微秒 +// 级别连续可调。而是会按照整行来取舍。这个函数的 +// 作用就是返回CMOS相机曝光一行对应的时间。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pfLineTime 指针,返回一行的曝光时间,单位为微秒。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ + +MVSDK_API CameraSdkStatus CameraGetExposureLineTime( + CameraHandle hCamera, + double* pfLineTime +); + +/******************************************************/ +// 函数名 : CameraGetExposureTime +// 功能描述 : 获得相机的曝光时间。请参见CameraSetExposureTime +// 的功能描述。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pfExposureTime 指针,返回当前的曝光时间,单位微秒。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetExposureTime( + CameraHandle hCamera, + double* pfExposureTime +); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief 获得相机的曝光时间范围 +/// \param [in] hCamera 相机的句柄。 +/// \param [out] pfMin 指针,返回曝光时间的最小值,单位微秒。 +/// \param [out] pfMax 指针,返回曝光时间的最大值,单位微秒。 +/// \param [out] pfStep 指针,返回曝光时间的步进值,单位微秒。 +/// \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 CameraGetExposureTimeRange( + CameraHandle hCamera, + double* pfMin, + double* pfMax, + double* pfStep + ); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief 设置多重曝光时间。单位为微秒。(此功能仅线阵相机支持) +/// \param [in] hCamera 相机的句柄。 +/// \param [in] index 曝光索引。 +/// \param [in] fExposureTime 曝光时间,单位微秒。 +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \note 对于CMOS传感器,其曝光的单位是按照行来计算的,因此,曝光时间并不能在微秒级别连续可调。而是会按照整行来取舍。在调用本函数设定曝光时间后,建议再调用@link #CameraGetMultiExposureTime @endlink来获得实际设定的值。 +/// \~english +/// \brief Set the multiple exposure time. The unit is microseconds. (This feature is only supported by line camera) +/// \param [in] hCamera Camera handle. +/// \param [in] index Exposure index. +/// \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 #CameraGetMultiExposureTime @endlink to get the actual set value. +MVSDK_API CameraSdkStatus CameraSetMultiExposureTime( + CameraHandle hCamera, + int index, + double fExposureTime + ); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief 获取多重曝光时间。单位为微秒。(此功能仅线阵相机支持) +/// \param [in] hCamera 相机的句柄。 +/// \param [in] index 曝光索引。 +/// \param [out] fExposureTime 返回曝光时间,单位微秒。 +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Get the multiple exposure time. The unit is microseconds. (This feature is only supported by line camera) +/// \param [in] hCamera Camera handle. +/// \param [in] index Exposure index. +/// \param [out] fExposureTime Returns 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 CameraGetMultiExposureTime( + CameraHandle hCamera, + int index, + double* fExposureTime + ); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief 设置多重曝光使能个数。(此功能仅线阵相机支持) +/// \param [in] hCamera 相机的句柄。 +/// \param [in] count 使能个数。 +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Set the number of multiple exposure enable. (This feature is only supported by line camera) +/// \param [in] hCamera Camera handle. +/// \param [in] count The number of exposures 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 CameraSetMultiExposureCount( + CameraHandle hCamera, + int count + ); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief 获取多重曝光使能个数。(此功能仅线阵相机支持) +/// \param [in] hCamera 相机的句柄。 +/// \param [out] count 使能个数。 +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Get the number of multiple exposure enable. (This feature is only supported by line camera) +/// \param [in] hCamera Camera handle. +/// \param [out] count The number of exposures 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 CameraGetMultiExposureCount( + CameraHandle hCamera, + int* count + ); + +/// @ingroup API_EXPOSURE +/// \~chinese +/// \brief 获取多重曝光的最大曝光个数。(此功能仅线阵相机支持) +/// \param [in] hCamera 相机的句柄。 +/// \param [out] max_count 支持的最大曝光个数。 +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Get the maximum number of exposures for multiple exposures. (This feature is only supported by line camera) +/// \param [in] hCamera Camera handle. +/// \param [out] max_count The maximum number of exposures supported. +/// \return Returns CAMERA_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 CameraGetMultiExposureMaxCount( + CameraHandle hCamera, + int* max_count + ); + +/******************************************************/ +// 函数名 : CameraSetAnalogGain +// 功能描述 : 设置相机的图像模拟增益值。该值乘以CameraGetCapability获得 +// 的相机属性结构体中sExposeDesc.fAnalogGainStep,就 +// 得到实际的图像信号放大倍数。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iAnalogGain 设定的模拟增益值。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetAnalogGain( + CameraHandle hCamera, + INT iAnalogGain +); + +/******************************************************/ +// 函数名 : CameraGetAnalogGain +// 功能描述 : 获得图像信号的模拟增益值。参见CameraSetAnalogGain +// 详细说明。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piAnalogGain 指针,返回当前的模拟增益值。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetAnalogGain( + CameraHandle hCamera, + INT* piAnalogGain +); + +/******************************************************/ +// 函数名 : CameraSetGain +// 功能描述 : 设置图像的数字增益。设定范围由CameraGetCapability +// 获得的相机属性结构体中sRgbGainRange成员表述。 +// 实际的放大倍数是设定值/100。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iRGain 红色通道的增益值。 +// iGGain 绿色通道的增益值。 +// iBGain 蓝色通道的增益值。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetGain( + CameraHandle hCamera, + int iRGain, + int iGGain, + int iBGain +); + + +/******************************************************/ +// 函数名 : CameraGetGain +// 功能描述 : 获得图像处理的数字增益。具体请参见CameraSetGain +// 的功能描述部分。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piRGain 指针,返回红色通道的数字增益值。 +// piGGain 指针,返回绿色通道的数字增益值。 +// piBGain 指针,返回蓝色通道的数字增益值。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus 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 +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetGamma( + CameraHandle hCamera, + int iGamma +); + +/******************************************************/ +// 函数名 : CameraGetGamma +// 功能描述 : 获得LUT动态生成模式下的Gamma值。请参考CameraSetGamma +// 函数的功能描述。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piGamma 指针,返回当前的Gamma值。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetGamma( + CameraHandle hCamera, + int* piGamma +); + +/******************************************************/ +// 函数名 : CameraSetContrast +// 功能描述 : 设定LUT动态生成模式下的对比度值。设定的值会 +// 马上保存在SDK内部,但是只有当相机处于动态 +// 参数生成的LUT模式时,才会生效。请参考CameraSetLutMode +// 的函数说明部分。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iContrast 设定的对比度值。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetContrast( + CameraHandle hCamera, + int iContrast +); + +/******************************************************/ +// 函数名 : CameraGetContrast +// 功能描述 : 获得LUT动态生成模式下的对比度值。请参考 +// CameraSetContrast函数的功能描述。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piContrast 指针,返回当前的对比度值。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetContrast( + CameraHandle hCamera, + int* piContrast +); + +/******************************************************/ +// 函数名 : CameraSetSaturation +// 功能描述 : 设定图像处理的饱和度。对黑白相机无效。 +// 设定范围由CameraGetCapability获得。100表示 +// 表示原始色度,不增强。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iSaturation 设定的饱和度值。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetSaturation( + CameraHandle hCamera, + int iSaturation +); + +/******************************************************/ +// 函数名 : CameraGetSaturation +// 功能描述 : 获得图像处理的饱和度。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piSaturation 指针,返回当前图像处理的饱和度值。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetSaturation( + CameraHandle hCamera, + int* piSaturation +); + +/******************************************************/ +// 函数名 : CameraSetMonochrome +// 功能描述 : 设置彩色转为黑白功能的使能。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// bEnable TRUE,表示将彩色图像转为黑白。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetMonochrome( + CameraHandle hCamera, + BOOL bEnable +); + +/******************************************************/ +// 函数名 : CameraGetMonochrome +// 功能描述 : 获得彩色转换黑白功能的使能状况。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pbEnable 指针。返回TRUE表示开启了彩色图像 +// 转换为黑白图像的功能。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetMonochrome( + CameraHandle hCamera, + BOOL* pbEnable +); + +/******************************************************/ +// 函数名 : CameraSetInverse +// 功能描述 : 设置彩图像颜色翻转功能的使能。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// bEnable TRUE,表示开启图像颜色翻转功能, +// 可以获得类似胶卷底片的效果。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetInverse( + CameraHandle hCamera, + BOOL bEnable +); + +/******************************************************/ +// 函数名 : CameraGetInverse +// 功能描述 : 获得图像颜色反转功能的使能状态。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pbEnable 指针,返回该功能使能状态。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetInverse( + CameraHandle hCamera, + BOOL* pbEnable +); + +/******************************************************/ +// 函数名 : CameraSetAntiFlick +// 功能描述 : 设置自动曝光时抗频闪功能的使能状态。对于手动 +// 曝光模式下无效。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// bEnable TRUE,开启抗频闪功能;FALSE,关闭该功能。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetAntiFlick( + CameraHandle hCamera, + BOOL bEnable +); + +/******************************************************/ +// 函数名 : CameraGetAntiFlick +// 功能描述 : 获得自动曝光时抗频闪功能的使能状态。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pbEnable 指针,返回该功能的使能状态。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetAntiFlick( + CameraHandle hCamera, + BOOL* pbEnable +); + +/******************************************************/ +// 函数名 : CameraGetLightFrequency +// 功能描述 : 获得自动曝光时,消频闪的频率选择。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piFrequencySel 指针,返回选择的索引号。0:50HZ 1:60HZ +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetLightFrequency( + CameraHandle hCamera, + int* piFrequencySel +); + +/******************************************************/ +// 函数名 : CameraSetLightFrequency +// 功能描述 : 设置自动曝光时消频闪的频率。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iFrequencySel 0:50HZ , 1:60HZ +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetLightFrequency( + CameraHandle hCamera, + int iFrequencySel +); + +/******************************************************/ +// 函数名 : CameraSetFrameSpeed +// 功能描述 : 设定相机输出图像的帧率。相机可供选择的帧率模式由 +// CameraGetCapability获得的信息结构体中iFrameSpeedDesc +// 表示最大帧率选择模式个数。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iFrameSpeed 选择的帧率模式索引号,范围从0到 +// CameraGetCapability获得的信息结构体中iFrameSpeedDesc - 1 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetFrameSpeed( + CameraHandle hCamera, + int iFrameSpeed +); + +/******************************************************/ +// 函数名 : CameraGetFrameSpeed +// 功能描述 : 获得相机输出图像的帧率选择索引号。具体用法参考 +// CameraSetFrameSpeed函数的功能描述部分。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piFrameSpeed 指针,返回选择的帧率模式索引号。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetFrameSpeed( + CameraHandle hCamera, + int* piFrameSpeed +); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief 设定相机的帧频(面阵)或行频(线阵)。(仅部分网口相机支持) +/// \param [in] hCamera 相机的句柄。 +/// \param [in] RateHZ 帧频或行频(<=0表示最大频率)。 +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Set the frame frequency (area) or line frequency (line scan). (only supported by some gige camera) +/// \param [in] hCamera Camera handle. +/// \param [in] RateHZ frame rate or line rate (<=0 means maximum frequency). +/// \return Returns CAMERA_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 CameraSetFrameRate( + CameraHandle hCamera, + int RateHZ + ); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief 获取设定的相机帧频(面阵)或行频(线阵) +/// \param [in] hCamera 相机的句柄。 +/// \param [out] RateHZ 帧频或行频(<=0表示最大频率)。 +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Get the frame frequency (area) or line frequency (line scan). +/// \param [in] hCamera Camera handle. +/// \param [out] RateHZ frame rate or line rate (<=0 means maximum frequency). +/// \return Returns CAMERA_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 CameraGetFrameRate( + CameraHandle hCamera, + int* RateHZ + ); + +/******************************************************/ +// 函数名 : CameraSetParameterMode +// 功能描述 : 设定参数存取的目标对象。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iMode 参数存取的对象。参考CameraDefine.h +// 中emSdkParameterMode的类型定义。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetParameterMode( + CameraHandle hCamera, + int iMode +); + +/******************************************************/ +// 函数名 : CameraGetParameterMode +// 功能描述 : +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// int* piTarget +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetParameterMode( + CameraHandle hCamera, + int* piTarget +); + +/******************************************************/ +// 函数名 : CameraSetParameterMask +// 功能描述 : 设置参数存取的掩码。参数加载和保存时会根据该 +// 掩码来决定各个模块参数的是否加载或者保存。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// uMask 掩码。参考CameraDefine.h中PROP_SHEET_INDEX +// 类型定义。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetParameterMask( + CameraHandle hCamera, + UINT uMask +); + +/******************************************************/ +// 函数名 : CameraSaveParameter +// 功能描述 : 保存当前相机参数到指定的参数组中。相机提供了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 +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSaveParameter( + CameraHandle hCamera, + int iTeam +); + + +/******************************************************/ +// 函数名 : CameraSaveParameterToFile +// 功能描述 : 保存当前相机参数到指定的文件中。该文件可以复制到 +// 别的电脑上供其他相机加载,也可以做参数备份用。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// sFileName 参数文件的完整路径。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSaveParameterToFile( + CameraHandle hCamera, + char* sFileName +); + + +/******************************************************/ +// 函数名 : CameraReadParameterFromFile +// 功能描述 : 从PC上指定的参数文件中加载参数。我公司相机参数 +// 保存在PC上为.config后缀的文件,位于安装下的 +// Camera\Configs文件夹中。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// *sFileName 参数文件的完整路径。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraReadParameterFromFile( + CameraHandle hCamera, + char* sFileName +); + +/******************************************************/ +// 函数名 : CameraLoadParameter +// 功能描述 : 加载指定组的参数到相机中。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iTeam PARAMETER_TEAM_A 加载A组参数, +// PARAMETER_TEAM_B 加载B组参数, +// PARAMETER_TEAM_C 加载C组参数, +// PARAMETER_TEAM_D 加载D组参数, +// PARAMETER_TEAM_DEFAULT 加载默认参数。 +// 类型定义参考CameraDefine.h中emSdkParameterTeam类型 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraLoadParameter( + CameraHandle hCamera, + int iTeam +); + +/******************************************************/ +// 函数名 : CameraGetCurrentParameterGroup +// 功能描述 : 获得当前选择的参数组。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piTeam 指针,返回当前选择的参数组。返回值 +// 参考CameraLoadParameter中iTeam参数。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetCurrentParameterGroup( + CameraHandle hCamera, + int* piTeam +); + +/******************************************************/ +// 函数名 : CameraSetTransPackLen +// 功能描述 : 设置相机传输图像数据的分包大小。 +// 目前的SDK版本中,该接口仅对GIGE接口相机有效, +// 用来控制网络传输的分包大小。对于支持巨帧的网卡, +// 我们建议选择8K的分包大小,可以有效的降低传输 +// 所占用的CPU处理时间。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iPackSel 分包长度选择的索引号。分包长度可由 +// 获得相机属性结构体中pPackLenDesc成员表述, +// iPackLenDesc成员则表示最大可选的分包模式个数。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetTransPackLen( + CameraHandle hCamera, + INT iPackSel +); + +/******************************************************/ +// 函数名 : CameraGetTransPackLen +// 功能描述 : 获得相机当前传输分包大小的选择索引号。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piPackSel 指针,返回当前选择的分包大小索引号。 +// 参见CameraSetTransPackLen中iPackSel的 +// 说明。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetTransPackLen( + CameraHandle hCamera, + INT* piPackSel +); + +/******************************************************/ +// 函数名 : CameraIsAeWinVisible +// 功能描述 : 获得自动曝光参考窗口的显示状态。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pbIsVisible 指针,返回TRUE,则表示当前窗口会 +// 被叠加在图像内容上。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraIsAeWinVisible( + CameraHandle hCamera, + BOOL* pbIsVisible +); + +/******************************************************/ +// 函数名 : CameraSetAeWinVisible +// 功能描述 : 设置自动曝光参考窗口的显示状态。当设置窗口状态 +// 为显示,调用CameraImageOverlay后,能够将窗口位置 +// 以矩形的方式叠加在图像上。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// bIsVisible TRUE,设置为显示;FALSE,不显示。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetAeWinVisible( + CameraHandle hCamera, + BOOL bIsVisible +); + +/******************************************************/ +// 函数名 : CameraGetAeWindow +// 功能描述 : 获得自动曝光参考窗口的位置。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piHOff 指针,返回窗口位置左上角横坐标值。 +// piVOff 指针,返回窗口位置左上角纵坐标值。 +// piWidth 指针,返回窗口的宽度。 +// piHeight 指针,返回窗口的高度。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetAeWindow( + CameraHandle hCamera, + INT* piHOff, + INT* piVOff, + INT* piWidth, + INT* piHeight +); + +/******************************************************/ +// 函数名 : CameraSetAeWindow +// 功能描述 : 设置自动曝光的参考窗口。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iHOff 窗口左上角的横坐标 +// iVOff 窗口左上角的纵坐标 +// iWidth 窗口的宽度 +// iHeight 窗口的高度 +// 如果iHOff、iVOff、iWidth、iHeight全部为0,则 +// 窗口设置为每个分辨率下的居中1/2大小。可以随着 +// 分辨率的变化而跟随变化;如果iHOff、iVOff、iWidth、iHeight +// 所决定的窗口位置范围超出了当前分辨率范围内, +// 则自动使用居中1/2大小窗口。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus 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 +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetMirror( + CameraHandle hCamera, + int iDir, + BOOL bEnable +); + +/******************************************************/ +// 函数名 : CameraGetMirror +// 功能描述 : 获得图像的镜像状态。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iDir 表示要获得的镜像方向。 +// 0,表示水平方向;1,表示垂直方向。 +// pbEnable 指针,返回TRUE,则表示iDir所指的方向 +// 镜像被使能。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetMirror( + CameraHandle hCamera, + int iDir, + BOOL* pbEnable +); + +/// @ingroup API_MIRROR +/// \~chinese +/// \brief 设置硬件镜像。分为水平和垂直两个方向。(仅部分网口、U3相机支持此功能) +/// \param [in] hCamera 相机的句柄。 +/// \param [in] iDir 表示镜像的方向。0,表示水平方向;1,表示垂直方向。 +/// \param [in] bEnable TRUE,使能镜像;FALSE,禁止镜像 +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Set up the hardware mirror. Divided into two directions, horizontal and vertical. (Only some GigE and U3 cameras support this feature) +/// \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 CameraSetHardwareMirror( + 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 hardware 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 CameraGetHardwareMirror( + 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 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 CameraGetRotate( + CameraHandle hCamera, + int* iRot + ); + +/******************************************************/ +// 函数名 : CameraGetWbWindow +// 功能描述 : 获得白平衡参考窗口的位置。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// PiHOff 指针,返回参考窗口的左上角横坐标 。 +// PiVOff 指针,返回参考窗口的左上角纵坐标 。 +// PiWidth 指针,返回参考窗口的宽度。 +// PiHeight 指针,返回参考窗口的高度。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus 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 +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetWbWindow( + CameraHandle hCamera, + INT iHOff, + INT iVOff, + INT iWidth, + INT iHeight +); + +/******************************************************/ +// 函数名 : CameraIsWbWinVisible +// 功能描述 : 获得白平衡窗口的显示状态。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pbShow 指针,返回TRUE,则表示窗口是可见的。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraIsWbWinVisible( + CameraHandle hCamera, + BOOL* pbShow +); + +/******************************************************/ +// 函数名 : CameraSetWbWinVisible +// 功能描述 : 设置白平衡窗口的显示状态。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// bShow TRUE,则表示设置为可见。在调用 +// CameraImageOverlay后,图像内容上将以矩形 +// 的方式叠加白平衡参考窗口的位置。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetWbWinVisible( + CameraHandle hCamera, + BOOL bShow +); + +/******************************************************/ +// 函数名 : CameraImageOverlay +// 功能描述 : 将输入的图像数据上叠加十字线、白平衡参考窗口、 +// 自动曝光参考窗口等图形。只有设置为可见状态的 +// 十字线和参考窗口才能被叠加上。 +// 注意,该函数的输入图像必须是RGB格式。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pRgbBuffer 图像数据缓冲区。 +// pFrInfo 图像的帧头信息。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraImageOverlay( + CameraHandle hCamera, + BYTE* pRgbBuffer, + tSdkFrameHead* pFrInfo +); + +/******************************************************/ +// 函数名 : CameraSetCrossLine +// 功能描述 : 设置指定十字线的参数。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iLine 表示要设置第几条十字线的状态。范围为[0,8],共9条。 +// x 十字线中心位置的横坐标值。 +// y 十字线中心位置的纵坐标值。 +// uColor 十字线的颜色,格式为(R|(G<<8)|(B<<16)) +// bVisible 十字线的显示状态。TRUE,表示显示。 +// 只有设置为显示状态的十字线,在调用 +// CameraImageOverlay后才会被叠加到图像上。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus 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 +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetCrossLine( + CameraHandle hCamera, + INT iLine, + INT* px, + INT* py, + UINT* pcolor, + BOOL* pbVisible +); + +/******************************************************/ +// 函数名 : CameraGetCapability +// 功能描述 : 获得相机的特性描述结构体。该结构体中包含了相机 +// 可设置的各种参数的范围信息。决定了相关函数的参数 +// 返回,也可用于动态创建相机的配置界面。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pCameraInfo 指针,返回该相机特性描述的结构体。 +// tSdkCameraCapbility在CameraDefine.h中定义。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetCapability( + CameraHandle hCamera, + tSdkCameraCapbility* pCameraInfo +); + +/******************************************************/ +// 函数名 : CameraGetCapabilityEx +// 功能描述 : 获得相机的特性描述结构体。该结构体中包含了相机 +// 可设置的各种参数的范围信息。决定了相关函数的参数 +// 返回,也可用于动态创建相机的配置界面。 +// 参数 : sDeviceModel 相机的型号,由扫描列表中获取 +// pCameraInfo 指针,返回该相机特性描述的结构体。 +// tSdkCameraCapbility在CameraDefine.h中定义。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetCapabilityEx( + char* sDeviceModel, + tSdkCameraCapbility* pCameraInfo, + PVOID hCameraHandle +); + + +/******************************************************/ +// 函数名 : CameraWriteSN +// 功能描述 : 设置相机的序列号。我公司相机序列号分为3级。 +// 0级的是我公司自定义的相机序列号,出厂时已经 +// 设定好,1级和2级留给二次开发使用。每级序列 +// 号长度都是32个字节。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pbySN 序列号的缓冲区。 +// iLevel 要设定的序列号级别,只能是1或者2。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraWriteSN( + CameraHandle hCamera, + BYTE* pbySN, + INT iLevel +); + +/******************************************************/ +// 函数名 : CameraReadSN +// 功能描述 : 读取相机指定级别的序列号。序列号的定义请参考 +// CameraWriteSN函数的功能描述部分。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pbySN 序列号的缓冲区。 +// iLevel 要读取的序列号级别。只能是1和2。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraReadSN( + CameraHandle hCamera, + BYTE* pbySN, + INT iLevel +); +/******************************************************/ +// 函数名 : CameraSetTriggerDelayTime +// 功能描述 : 设置硬件触发模式下的触发延时时间,单位微秒。 +// 当硬触发信号来临后,经过指定的延时,再开始采集 +// 图像。仅部分型号的相机支持该功能。具体请查看 +// 产品说明书。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// uDelayTimeUs 硬触发延时。单位微秒。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetTriggerDelayTime( + CameraHandle hCamera, + UINT uDelayTimeUs +); + +/******************************************************/ +// 函数名 : CameraGetTriggerDelayTime +// 功能描述 : 获得当前设定的硬触发延时时间。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// puDelayTimeUs 指针,返回延时时间,单位微秒。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetTriggerDelayTime( + CameraHandle hCamera, + UINT* puDelayTimeUs +); + +/******************************************************/ +// 函数名 : CameraSetTriggerPeriodTime +// 功能描述 : 一次触发多帧时,设置2帧之间的间隔时间。 +// 仅部分型号的相机支持该功能。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// time 间隔时间(微秒) +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetTriggerPeriodTime( + CameraHandle hCamera, + UINT time +); + +/******************************************************/ +// 函数名 : CameraGetTriggerPeriodTime +// 功能描述 : 获取当前设置的间隔时间。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// time 间隔时间(微秒) +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetTriggerPeriodTime( + CameraHandle hCamera, + UINT* time +); + +/******************************************************/ +// 函数名 : CameraSetTriggerCount +// 功能描述 : 设置触发模式下的触发帧数。对软件触发和硬件触发 +// 模式都有效。默认为1帧,即一次触发信号采集一帧图像。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iCount 一次触发采集的帧数。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetTriggerCount( + CameraHandle hCamera, + INT iCount +); + +/******************************************************/ +// 函数名 : CameraGetTriggerCount +// 功能描述 : 获得一次触发的帧数。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// INT* piCount +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetTriggerCount( + CameraHandle hCamera, + INT* piCount +); + +/******************************************************/ +// 函数名 : CameraSoftTrigger +// 功能描述 : 执行一次软触发。执行后,会触发由CameraSetTriggerCount +// 指定的帧数。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSoftTrigger( + CameraHandle hCamera +); + +/******************************************************/ +// 函数名 : CameraSetTriggerMode +// 功能描述 : 设置相机的触发模式。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iModeSel 模式选择索引号。可设定的模式由 +// CameraGetCapability函数获取。请参考 +// CameraDefine.h中tSdkCameraCapbility的定义。 +// 一般情况,0表示连续采集模式;1表示 +// 软件触发模式;2表示硬件触发模式。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetTriggerMode( + CameraHandle hCamera, + int iModeSel +); + +/******************************************************/ +// 函数名 : CameraGetTriggerMode +// 功能描述 : 获得相机的触发模式。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piModeSel 指针,返回当前选择的相机触发模式的索引号。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus 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 +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetStrobeMode( + CameraHandle hCamera, + INT iMode +); + +/******************************************************/ +// 函数名 : CameraGetStrobeMode +// 功能描述 : 或者当前STROBE信号设置的模式。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piMode 指针,返回STROBE_SYNC_WITH_TRIG_AUTO,STROBE_SYNC_WITH_TRIG_MANUAL、STROBE_ALWAYS_HIGH或者STROBE_ALWAYS_LOW。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetStrobeMode( + CameraHandle hCamera, + INT* piMode +); + +/******************************************************/ +// 函数名 : CameraSetStrobeDelayTime +// 功能描述 : 当STROBE信号处于STROBE_SYNC_WITH_TRIG时,通过该函数设置其相对触发信号延时时间。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// uDelayTimeUs 相对触发信号的延时时间,单位为us。可以为0,但不能为负数。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetStrobeDelayTime( + CameraHandle hCamera, + UINT uDelayTimeUs +); + +/******************************************************/ +// 函数名 : CameraGetStrobeDelayTime +// 功能描述 : 当STROBE信号处于STROBE_SYNC_WITH_TRIG时,通过该函数获得其相对触发信号延时时间。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// upDelayTimeUs 指针,返回延时时间,单位us。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetStrobeDelayTime( + CameraHandle hCamera, + UINT* upDelayTimeUs +); + +/******************************************************/ +// 函数名 : CameraSetStrobePulseWidth +// 功能描述 : 当STROBE信号处于STROBE_SYNC_WITH_TRIG时,通过该函数设置其脉冲宽度。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// uTimeUs 脉冲的宽度,单位为时间us。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetStrobePulseWidth( + CameraHandle hCamera, + UINT uTimeUs +); + +/******************************************************/ +// 函数名 : CameraGetStrobePulseWidth +// 功能描述 : 当STROBE信号处于STROBE_SYNC_WITH_TRIG时,通过该函数获得其脉冲宽度。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// upTimeUs 指针,返回脉冲宽度。单位为时间us。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus 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 +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetStrobePolarity( + CameraHandle hCamera, + INT uPolarity +); + +/******************************************************/ +// 函数名 : CameraGetStrobePolarity +// 功能描述 : 获得相机当前STROBE信号的有效极性。默认为高电平有效。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// ipPolarity 指针,返回STROBE信号当前的有效极性。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetStrobePolarity( + CameraHandle hCamera, + INT* upPolarity +); + +/******************************************************/ +// 函数名 : CameraSetExtTrigSignalType +// 功能描述 : 设置相机外触发信号的种类。上边沿、下边沿、或者高、低电平方式。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iType 外触发信号种类,返回值参考CameraDefine.h中 +// emExtTrigSignal类型定义。 + +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetExtTrigSignalType( + CameraHandle hCamera, + INT iType +); + +/******************************************************/ +// 函数名 : CameraGetExtTrigSignalType +// 功能描述 : 获得相机当前外触发信号的种类。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// ipType 指针,返回外触发信号种类,返回值参考CameraDefine.h中 +// emExtTrigSignal类型定义。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetExtTrigSignalType( + CameraHandle hCamera, + INT* ipType +); + +/******************************************************/ +// 函数名 : CameraSetExtTrigShutterType +// 功能描述 : 设置外触发模式下,相机快门的方式,默认为标准快门方式。 +// 部分滚动快门的CMOS相机支持GRR方式。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iType 外触发快门方式。参考CameraDefine.h中emExtTrigShutterMode类型。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetExtTrigShutterType( + CameraHandle hCamera, + INT iType +); + +/******************************************************/ +// 函数名 : CameraSetExtTrigShutterType +// 功能描述 : 获得外触发模式下,相机快门的方式,默认为标准快门方式。 +// 部分滚动快门的CMOS相机支持GRR方式。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// ipType 指针,返回当前设定的外触发快门方式。返回值参考 +// CameraDefine.h中emExtTrigShutterMode类型。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetExtTrigShutterType( + CameraHandle hCamera, + INT* ipType +); + +/******************************************************/ +// 函数名 : CameraSetExtTrigDelayTime +// 功能描述 : 设置外触发信号延时时间,默认为0,单位为微秒。 +// 当设置的值uDelayTimeUs不为0时,相机接收到外触发信号后,将延时uDelayTimeUs个微秒后再进行图像捕获。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// uDelayTimeUs 延时时间,单位为微秒,默认为0. +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetExtTrigDelayTime( + CameraHandle hCamera, + UINT uDelayTimeUs +); + +/******************************************************/ +// 函数名 : CameraGetExtTrigDelayTime +// 功能描述 : 获得设置的外触发信号延时时间,默认为0,单位为微秒。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// UINT* upDelayTimeUs +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetExtTrigDelayTime( + CameraHandle hCamera, + UINT* upDelayTimeUs +); + +/******************************************************/ +// 函数名 : CameraSetExtTrigBufferedDelayTime +// 功能描述 : 设置外触发信号延时时间,默认为0,单位为微秒。 +// 当设置的值uDelayTimeUs不为0时,相机接收到外触发信号后,将延时uDelayTimeUs个微秒后再进行图像捕获。 +// 并且会把延时期间收到的触发信号缓存起来,被缓存的信号也将延时uDelayTimeUs个微秒后生效(最大缓存个数128)。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// uDelayTimeUs 延时时间,单位为微秒,默认为0. +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetExtTrigBufferedDelayTime( + CameraHandle hCamera, + UINT uDelayTimeUs +); + +/******************************************************/ +// 函数名 : CameraGetExtTrigBufferedDelayTime +// 功能描述 : 获得设置的外触发信号延时时间,默认为0,单位为微秒。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// puDelayTimeUs 延时时间,单位为微秒,默认为0. +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetExtTrigBufferedDelayTime( + CameraHandle hCamera, + UINT* puDelayTimeUs +); + +/******************************************************/ +// 函数名 : CameraSetExtTrigJitterTime +// 功能描述 : 设置相机外触发信号的消抖时间。默认为0,单位为微秒。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// UINT uTimeUs +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetExtTrigJitterTime( + CameraHandle hCamera, + UINT uTimeUs +); + +/******************************************************/ +// 函数名 : CameraGetExtTrigJitterTime +// 功能描述 : 获得设置的相机外触发消抖时间,默认为0.单位为微妙 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// UINT* upTimeUs +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetExtTrigJitterTime( + CameraHandle hCamera, + UINT* upTimeUs +); + +/******************************************************/ +// 函数名 : CameraGetExtTrigCapability +// 功能描述 : 获得相机外触发的属性掩码 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// puCapabilityMask 指针,返回该相机外触发特性掩码,掩码参考CameraDefine.h中 +// EXT_TRIG_MASK_ 开头的宏定义。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetExtTrigCapability( + CameraHandle hCamera, + UINT* puCapabilityMask +); + + +/******************************************************/ +// 函数名 : CameraGetResolutionForSnap +// 功能描述 : 获得抓拍模式下的分辨率选择索引号。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pImageResolution 指针,返回抓拍模式的分辨率。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetResolutionForSnap( + CameraHandle hCamera, + tSdkImageResolution* pImageResolution +); + +/******************************************************/ +// 函数名 : CameraSetResolutionForSnap +// 功能描述 : 设置抓拍模式下相机输出图像的分辨率。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pImageResolution 如果pImageResolution->iWidth +// 和 pImageResolution->iHeight都为0, +// 则表示设定为跟随当前预览分辨率。抓 +// 怕到的图像的分辨率会和当前设定的 +// 预览分辨率一样。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetResolutionForSnap( + CameraHandle hCamera, + tSdkImageResolution* pImageResolution +); + +/******************************************************/ +// 函数名 : CameraCustomizeResolution +// 功能描述 : 打开分辨率自定义面板,并通过可视化的方式 +// 来配置一个自定义分辨率。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pImageCustom 指针,返回自定义的分辨率。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraCustomizeResolution( + CameraHandle hCamera, + tSdkImageResolution* pImageCustom +); + +/******************************************************/ +// 函数名 : CameraCustomizeReferWin +// 功能描述 : 打开参考窗口自定义面板。并通过可视化的方式来 +// 获得一个自定义窗口的位置。一般是用自定义白平衡 +// 和自动曝光的参考窗口。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iWinType 要生成的参考窗口的用途。0,自动曝光参考窗口; +// 1,白平衡参考窗口。 +// hParent 调用该函数的窗口的句柄。可以为NULL。 +// piHOff 指针,返回自定义窗口的左上角横坐标。 +// piVOff 指针,返回自定义窗口的左上角纵坐标。 +// piWidth 指针,返回自定义窗口的宽度。 +// piHeight 指针,返回自定义窗口的高度。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus 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 +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraShowSettingPage( + CameraHandle hCamera, + BOOL bShow +); + +/******************************************************/ +// 函数名 : CameraCreateSettingPage +// 功能描述 : 创建该相机的属性配置窗口。调用该函数,SDK内部会 +// 帮您创建好相机的配置窗口,省去了您重新开发相机 +// 配置界面的时间。强烈建议使用您使用该函数让 +// SDK为您创建好配置窗口。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// hParent 应用程序主窗口的句柄。可以为NULL。 +// pWinText 字符串指针,窗口显示的标题栏。 +// pCallbackFunc 窗口消息的回调函数,当相应的事件发生时, +// pCallbackFunc所指向的函数会被调用, +// 例如切换了参数之类的操作时,pCallbackFunc +// 被回调时,在入口参数处指明了消息类型。 +// 这样可以方便您自己开发的界面和我们生成的UI +// 之间进行同步。该参数可以为NULL。 +// pCallbackCtx 回调函数的附加参数。可以为NULL。pCallbackCtx +// 会在pCallbackFunc被回调时,做为参数之一传入。 +// 您可以使用该参数来做一些灵活的判断。 +// uReserved 预留。必须设置为0。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraCreateSettingPage( + CameraHandle hCamera, + HWND hParent, + char* pWinText, + CAMERA_PAGE_MSG_PROC pCallbackFunc, + PVOID pCallbackCtx, + UINT uReserved +); + +/******************************************************/ +// 函数名 : CameraCreateSettingPageEx +// 功能描述 : 创建该相机的属性配置窗口。调用该函数,SDK内部会 +// 帮您创建好相机的配置窗口,省去了您重新开发相机 +// 配置界面的时间。强烈建议使用您使用该函数让 +// SDK为您创建好配置窗口。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraCreateSettingPageEx( + CameraHandle hCamera +); + + +/******************************************************/ +// 函数名 : CameraSetActiveSettingSubPage +// 功能描述 : 设置相机配置窗口的激活页面。相机配置窗口有多个 +// 子页面构成,该函数可以设定当前哪一个子页面 +// 为激活状态,显示在最前端。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// index 子页面的索引号。参考CameraDefine.h中 +// PROP_SHEET_INDEX的定义。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetActiveSettingSubPage( + CameraHandle hCamera, + INT index +); + +/******************************************************/ +// 函数名 : CameraSpecialControl +// 功能描述 : 相机一些特殊配置所调用的接口,二次开发时一般不需要 +// 调用。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// dwCtrlCode 控制码。 +// dwParam 控制子码,不同的dwCtrlCode时,意义不同。 +// lpData 附加参数。不同的dwCtrlCode时,意义不同。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSpecialControl( + CameraHandle hCamera, + DWORD dwCtrlCode, + DWORD dwParam, + LPVOID lpData +); + +/******************************************************/ +// 函数名 : CameraGetFrameStatistic +// 功能描述 : 获得相机接收帧率的统计信息,包括错误帧和丢帧的情况。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// psFrameStatistic 指针,返回统计信息。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetFrameStatistic( + CameraHandle hCamera, + tSdkFrameStatistic* psFrameStatistic +); + +/******************************************************/ +// 函数名 : CameraGetStatisticResend +// 功能描述 : 获得相机统计信息之重传数量 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pResendCount 指针,返回重传数量。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetStatisticResend( + CameraHandle hCamera, + UINT* pResendCount +); + +/******************************************************/ +// 函数名 : CameraSetNoiseFilter +// 功能描述 : 设置图像降噪模块的使能状态。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// bEnable TRUE,使能;FALSE,禁止。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetNoiseFilter( + CameraHandle hCamera, + BOOL bEnable +); + +/******************************************************/ +// 函数名 : CameraGetNoiseFilterState +// 功能描述 : 获得图像降噪模块的使能状态。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// *pEnable 指针,返回状态。TRUE,为使能。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetNoiseFilterState( + CameraHandle hCamera, + BOOL* pEnable +); + +/******************************************************/ +// 函数名 : CameraRstTimeStamp +// 功能描述 : 复位图像采集的时间戳,从0开始。 +// 参数 : CameraHandle hCamera +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraRstTimeStamp( + CameraHandle hCamera +); + +/******************************************************/ +// 函数名 : CameraSaveUserData +// 功能描述 : 将用户自定义的数据保存到相机的非易性存储器中。 +// 每个型号的相机可能支持的用户数据区最大长度不一样。 +// 可以从设备的特性描述中获取该长度信息。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// uStartAddr 起始地址,从0开始。 +// pbData 数据缓冲区指针 +// ilen 写入数据的长度,ilen + uStartAddr必须 +// 小于用户区最大长度 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSaveUserData( + CameraHandle hCamera, + UINT uStartAddr, + BYTE *pbData, + int ilen +); + +/******************************************************/ +// 函数名 : CameraLoadUserData +// 功能描述 : 从相机的非易性存储器中读取用户自定义的数据。 +// 每个型号的相机可能支持的用户数据区最大长度不一样。 +// 可以从设备的特性描述中获取该长度信息。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// uStartAddr 起始地址,从0开始。 +// pbData 数据缓冲区指针,返回读到的数据。 +// ilen 读取数据的长度,ilen + uStartAddr必须 +// 小于用户区最大长度 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraLoadUserData( + CameraHandle hCamera, + UINT uStartAddr, + BYTE *pbData, + int ilen +); + +/******************************************************/ +// 函数名 : CameraGetFriendlyName +// 功能描述 : 读取用户自定义的设备昵称。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pName 指针,返回指向0结尾的字符串, +// 设备昵称不超过32个字节,因此该指针 +// 指向的缓冲区必须大于等于32个字节空间。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetFriendlyName( + CameraHandle hCamera, + char* pName +); + +/******************************************************/ +// 函数名 : CameraSetFriendlyName +// 功能描述 : 设置用户自定义的设备昵称。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pName 指针,指向0结尾的字符串, +// 设备昵称不超过32个字节,因此该指针 +// 指向字符串必须小于等于32个字节空间。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetFriendlyName( + CameraHandle hCamera, + char* pName +); + +/******************************************************/ +// 函数名 : CameraSdkGetVersionString +// 功能描述 : +// 参数 : pVersionString 指针,返回SDK版本字符串。 +// 该指针指向的缓冲区大小必须大于 +// 32个字节 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSdkGetVersionString( + char* pVersionString +); + +/******************************************************/ +// 函数名 : CameraCheckFwUpdate +// 功能描述 : 检测固件版本,是否需要升级。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pNeedUpdate 指针,返回固件检测状态,TRUE表示需要更新 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraCheckFwUpdate( + CameraHandle hCamera, + BOOL* pNeedUpdate +); + +/******************************************************/ +// 函数名 : CameraGetFirmwareVision +// 功能描述 : 获得固件版本的字符串 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pVersion 必须指向一个大于32字节的缓冲区, +// 返回固件的版本字符串。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetFirmwareVersion( + CameraHandle hCamera, + char* pVersion +); + +/******************************************************/ +// 函数名 : CameraGetEnumInfo +// 功能描述 : 获得指定设备的枚举信息 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pCameraInfo 指针,返回设备的枚举信息。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetEnumInfo( + CameraHandle hCamera, + tSdkCameraDevInfo* pCameraInfo +); + +/******************************************************/ +// 函数名 : CameraGetInerfaceVersion +// 功能描述 : 获得指定设备接口的版本 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pVersion 指向一个大于32字节的缓冲区,返回接口版本字符串。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus 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 +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetIOState( + CameraHandle hCamera, + INT iOutputIOIndex, + UINT uState +); + +/// @ingroup API_GPIO +/// \~chinese +/// \brief 读取指定IO的电平状态,IO为输出型IO,相机预留可编程输出IO的个数由@link #tSdkCameraCapbility.iOutputIoCounts @endlink决定。 +/// \param [in] hCamera 相机的句柄。 +/// \param [in] iOutputIOIndex 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 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 [out] puState return 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 CameraGetOutPutIOState( + CameraHandle hCamera, + INT iOutputIOIndex, + UINT* puState + ); + +/******************************************************/ +// 函数名 : CameraGetIOState +// 功能描述 : 设置指定IO的电平状态,IO为输入型IO,相机 +// 预留可编程输出IO的个数由tSdkCameraCapbility中 +// iInputIoCounts决定。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iInputIOIndex IO的索引号,从0开始。 +// puState 指针,返回IO状态,1为高,0为低 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetIOState( + CameraHandle hCamera, + INT iInputIOIndex, + UINT* puState +); + + + +/******************************************************/ +// 函数名 : CameraSetInPutIOMode +// 功能描述 : 设置输入IO的模式,相机 +// 预留可编程输出IO的个数由tSdkCameraCapbility中 +// iInputIoCounts决定。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iInputIOIndex IO的索引号,从0开始。 +// iMode IO模式,参考CameraDefine.h中emCameraGPIOMode +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetInPutIOMode( + CameraHandle hCamera, + INT iInputIOIndex, + INT iMode + ); + +/// @ingroup API_GPIO +/// \~chinese +/// \brief 获取输入IO的模式 +/// \param [in] hCamera 相机的句柄。 +/// \param [in] iInputIOIndex IO的索引号,从0开始。 +/// \param [out] piMode IO模式,参考@link #emCameraGPIOMode @endlink +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Get the input IO mode +/// \param [in] hCamera Camera handle. +/// \param [in] iInputIOIndex IO index, starting from 0. +/// \param [out] piMode 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 CameraGetInPutIOMode( + CameraHandle hCamera, + INT iInputIOIndex, + INT* piMode + ); + +/******************************************************/ +// 函数名 : CameraSetOutPutIOMode +// 功能描述 : 设置输出IO的模式,相机 +// 预留可编程输出IO的个数由tSdkCameraCapbility中 +// iOutputIoCounts决定。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iOutputIOIndex IO的索引号,从0开始。 +// iMode IO模式,参考CameraDefine.h中emCameraGPIOMode +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetOutPutIOMode( + CameraHandle hCamera, + INT iOutputIOIndex, + INT iMode + ); + +/// @ingroup API_GPIO +/// \~chinese +/// \brief 获取输出IO的模式 +/// \param [in] hCamera 相机的句柄。 +/// \param [in] iOutputIOIndex IO的索引号,从0开始。 +/// \param [out] piMode IO模式,参考@link #emCameraGPIOMode @endlink +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Get the output IO mode +/// \param [in] hCamera Camera handle. +/// \param [in] iOutputIOIndex IO index, starting from 0. +/// \param [out] piMode 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 CameraGetOutPutIOMode( + CameraHandle hCamera, + INT iOutputIOIndex, + INT* piMode + ); + +/// @ingroup API_GPIO +/// \~chinese +/// \brief 获取输入IO的模式支持能力 +/// \param [in] hCamera 相机的句柄。 +/// \param [in] iInputIOIndex IO的索引号,从0开始。 +/// \param [out] piCapbility IO模式支持位掩码 +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Get the mode support capability of the input IO +/// \param [in] hCamera Camera handle. +/// \param [in] iInputIOIndex IO index, starting from 0. +/// \param [out] piCapbility IO mode support bit mask +/// \return Returns CAMERA_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 CameraGetInPutIOModeCapbility( + CameraHandle hCamera, + INT iInputIOIndex, + UINT* piCapbility + ); + +/// @ingroup API_GPIO +/// \~chinese +/// \brief 获取输出IO的模式支持能力 +/// \param [in] hCamera 相机的句柄。 +/// \param [in] iOutputIOIndex IO的索引号,从0开始。 +/// \param [out] piCapbility IO模式支持位掩码 +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Get the mode support capability of the output IO +/// \param [in] hCamera Camera handle. +/// \param [in] iOutputIOIndex IO index, starting from 0. +/// \param [out] piCapbility IO mode support bit mask +/// \return Returns CAMERA_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 CameraGetOutPutIOModeCapbility( + CameraHandle hCamera, + INT iOutputIOIndex, + UINT* piCapbility + ); + +/******************************************************/ +// 函数名 : CameraSetOutPutPWM +// 功能描述 : 设置PWM型输出的参数,相机 +// 预留可编程输出IO的个数由tSdkCameraCapbility中 +// iOutputIoCounts决定。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iOutputIOIndex IO的索引号,从0开始。 +// iCycle PWM的周期,单位(us) +// uDuty 占用比,取值1%~99% +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetOutPutPWM( + CameraHandle hCamera, + INT iOutputIOIndex, + UINT iCycle, + UINT uDuty + ); + +/// @ingroup API_GPIO +/// \~chinese +/// \brief 设置编码器有效方向 +/// \param [in] hCamera 相机的句柄。 +/// \param [in] dir 有效方向(0:正反转都有效 1:顺时针(A相超前于B) 2:逆时针) +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Set the effective direction of the rotary encoder +/// \param [in] hCamera Camera handle. +/// \param [in] dir Valid direction (0: Both positive and negative are valid 1: Clockwise (A phase leads B) 2: Counterclockwise) +/// \return Returns CAMERA_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 CameraSetRotaryEncDir( + CameraHandle hCamera, + INT dir + ); + +/// @ingroup API_GPIO +/// \~chinese +/// \brief 获取编码器有效方向 +/// \param [in] hCamera 相机的句柄。 +/// \param [out] dir 有效方向(0:正反转都有效 1:顺时针(A相超前于B) 2:逆时针) +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Get the effective direction of the rotary encoder +/// \param [in] hCamera Camera handle. +/// \param [out] dir Valid direction (0: Both positive and negative are valid 1: Clockwise (A phase leads B) 2: Counterclockwise) +/// \return Returns CAMERA_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 CameraGetRotaryEncDir( + CameraHandle hCamera, + INT* dir + ); + +/// @ingroup API_GPIO +/// \~chinese +/// \brief 设置编码器频率 +/// \param [in] hCamera 相机的句柄。 +/// \param [in] mul 倍频 +/// \param [in] div 分频 +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Set the frequency of the rotary encoder +/// \param [in] hCamera Camera handle. +/// \param [in] mul frequency multiplier +/// \param [in] div frequency division +/// \return Returns CAMERA_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 CameraSetRotaryEncFreq( + CameraHandle hCamera, + INT mul, + INT div + ); + +/// @ingroup API_GPIO +/// \~chinese +/// \brief 获取编码器频率 +/// \param [in] hCamera 相机的句柄。 +/// \param [out] mul 倍频 +/// \param [out] div 分频 +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Get the frequency of the rotary encoder +/// \param [in] hCamera Camera handle. +/// \param [out] mul frequency multiplier +/// \param [out] div frequency division +/// \return Returns CAMERA_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 CameraGetRotaryEncFreq( + CameraHandle hCamera, + INT* mul, + INT* div + ); + +/// @ingroup API_GPIO +/// \~chinese +/// \brief 设置输入IO的格式 +/// \param [in] hCamera 相机的句柄。 +/// \param [in] iInputIOIndex IO的索引号,从0开始。 +/// \param [in] iFormat IO格式,参考@link #emCameraGPIOFormat @endlink +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Set the input IO format +/// \param [in] hCamera Camera handle. +/// \param [in] iInputIOIndex IO index, starting from 0. +/// \param [in] iFormat IO format, reference @link #emCameraGPIOFormat @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 CameraSetInPutIOFormat( + CameraHandle hCamera, + INT iInputIOIndex, + INT iFormat + ); + +/// @ingroup API_GPIO +/// \~chinese +/// \brief 获取输入IO的格式 +/// \param [in] hCamera 相机的句柄。 +/// \param [in] iInputIOIndex IO的索引号,从0开始。 +/// \param [out] piFormat IO格式,参考@link #emCameraGPIOFormat @endlink +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Get the input IO format +/// \param [in] hCamera Camera handle. +/// \param [in] iInputIOIndex IO index, starting from 0. +/// \param [out] piFormat IO format, reference @link #emCameraGPIOFormat @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 CameraGetInPutIOFormat( + CameraHandle hCamera, + INT iInputIOIndex, + INT* piFormat + ); + +/// @ingroup API_GPIO +/// \~chinese +/// \brief 设置输出IO的格式 +/// \param [in] hCamera 相机的句柄。 +/// \param [in] iOutputIOIndex IO的索引号,从0开始。 +/// \param [in] iFormat IO格式,参考@link #emCameraGPIOFormat @endlink +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Set the output IO format +/// \param [in] hCamera Camera handle. +/// \param [in] iOutputIOIndex IO index, starting from 0. +/// \param [in] iFormat IO format, reference @link #emCameraGPIOFormat @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 CameraSetOutPutIOFormat( + CameraHandle hCamera, + INT iOutputIOIndex, + INT iFormat + ); + +/// @ingroup API_GPIO +/// \~chinese +/// \brief 获取输出IO的格式 +/// \param [in] hCamera 相机的句柄。 +/// \param [in] iOutputIOIndex IO的索引号,从0开始。 +/// \param [out] piFormat IO格式,参考@link #emCameraGPIOFormat @endlink +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Get the output IO format +/// \param [in] hCamera Camera handle. +/// \param [in] iOutputIOIndex IO index, starting from 0. +/// \param [out] piFormat IO format, reference @link #emCameraGPIOFormat @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 CameraGetOutPutIOFormat( + CameraHandle hCamera, + INT iOutputIOIndex, + INT* piFormat + ); + +/// @ingroup API_GPIO +/// \~chinese +/// \brief 获取输入IO的格式支持能力 +/// \param [in] hCamera 相机的句柄。 +/// \param [in] iInputIOIndex IO的索引号,从0开始。 +/// \param [out] piCapbility IO格式支持位掩码 +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Get the format support capability of the input IO +/// \param [in] hCamera Camera handle. +/// \param [in] iInputIOIndex IO index, starting from 0. +/// \param [out] piCapbility IO format support bit mask +/// \return Returns CAMERA_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 CameraGetInPutIOFormatCapbility( + CameraHandle hCamera, + INT iInputIOIndex, + UINT* piCapbility + ); + +/// @ingroup API_GPIO +/// \~chinese +/// \brief 获取输出IO的格式支持能力 +/// \param [in] hCamera 相机的句柄。 +/// \param [in] iOutputIOIndex IO的索引号,从0开始。 +/// \param [out] piCapbility IO格式支持位掩码 +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Get the format support capability of the output IO +/// \param [in] hCamera Camera handle. +/// \param [in] iOutputIOIndex IO index, starting from 0. +/// \param [out] piCapbility IO format support bit mask +/// \return Returns CAMERA_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 CameraGetOutPutIOFormatCapbility( + CameraHandle hCamera, + INT iOutputIOIndex, + UINT* piCapbility + ); + +/******************************************************/ +// 函数名 : CameraSetOutPutDelayTime +// 功能描述 : 设置输出延时,相机 +// 预留可编程输出IO的个数由tSdkCameraCapbility中 +// iOutputIoCounts决定。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iOutputIOIndex IO的索引号,从0开始。 +// uDelayTimeUs 延时,单位(us) +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetOutPutDelayTime( + CameraHandle hCamera, + INT iOutputIOIndex, + UINT uDelayTimeUs + ); + +/******************************************************/ +// 函数名 : CameraSetOutPutPulseWidth +// 功能描述 : 设置输出脉宽,相机 +// 预留可编程输出IO的个数由tSdkCameraCapbility中 +// iOutputIoCounts决定。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iOutputIOIndex IO的索引号,从0开始。 +// uTimeUs 脉宽,单位(us) +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetOutPutPulseWidth( + CameraHandle hCamera, + INT iOutputIOIndex, + UINT uTimeUs + ); + +/******************************************************/ +// 函数名 : CameraSetOutPutPolarity +// 功能描述 : 设置输出极性,相机 +// 预留可编程输出IO的个数由tSdkCameraCapbility中 +// iOutputIoCounts决定。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iOutputIOIndex IO的索引号,从0开始。 +// uPolarity 0:正向 1:反向 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetOutPutPolarity( + CameraHandle hCamera, + INT iOutputIOIndex, + UINT uPolarity + ); + +/******************************************************/ +// 函数名 : CameraSetAeAlgorithm +// 功能描述 : 设置自动曝光时选择的算法,不同的算法适用于 +// 不同的场景。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iIspProcessor 选择执行该算法的对象,参考CameraDefine.h +// emSdkIspProcessor的定义 +// iAeAlgorithmSel 要选择的算法编号。从0开始,最大值由tSdkCameraCapbility +// 中iAeAlmSwDesc和iAeAlmHdDesc决定。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetAeAlgorithm( + CameraHandle hCamera, + INT iIspProcessor, + INT iAeAlgorithmSel +); + +/******************************************************/ +// 函数名 : CameraGetAeAlgorithm +// 功能描述 : 获得当前自动曝光所选择的算法 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iIspProcessor 选择执行该算法的对象,参考CameraDefine.h +// emSdkIspProcessor的定义 +// piAeAlgorithmSel 返回当前选择的算法编号。从0开始,最大值由tSdkCameraCapbility +// 中iAeAlmSwDesc和iAeAlmHdDesc决定。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetAeAlgorithm( + CameraHandle hCamera, + INT iIspProcessor, + INT* piAlgorithmSel +); + +/******************************************************/ +// 函数名 : CameraSetBayerDecAlgorithm +// 功能描述 : 设置Bayer数据转彩色的算法。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iIspProcessor 选择执行该算法的对象,参考CameraDefine.h +// emSdkIspProcessor的定义 +// iAlgorithmSel 要选择的算法编号。从0开始,最大值由tSdkCameraCapbility +// 中iBayerDecAlmSwDesc和iBayerDecAlmHdDesc决定。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetBayerDecAlgorithm( + CameraHandle hCamera, + INT iIspProcessor, + INT iAlgorithmSel +); + +/******************************************************/ +// 函数名 : CameraGetBayerDecAlgorithm +// 功能描述 : 获得Bayer数据转彩色所选择的算法。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iIspProcessor 选择执行该算法的对象,参考CameraDefine.h +// emSdkIspProcessor的定义 +// piAlgorithmSel 返回当前选择的算法编号。从0开始,最大值由tSdkCameraCapbility +// 中iBayerDecAlmSwDesc和iBayerDecAlmHdDesc决定。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetBayerDecAlgorithm( + CameraHandle hCamera, + INT iIspProcessor, + INT* piAlgorithmSel +); + +/******************************************************/ +// 函数名 : CameraSetIspProcessor +// 功能描述 : 设置图像处理单元的算法执行对象,由PC端或者相机端 +// 来执行算法,当由相机端执行时,会降低PC端的CPU占用率。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iIspProcessor 参考CameraDefine.h中 +// emSdkIspProcessor的定义。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetIspProcessor( + CameraHandle hCamera, + INT iIspProcessor +); + +/******************************************************/ +// 函数名 : CameraGetIspProcessor +// 功能描述 : 获得图像处理单元的算法执行对象。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piIspProcessor 返回选择的对象,返回值参考CameraDefine.h中 +// emSdkIspProcessor的定义。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetIspProcessor( + CameraHandle hCamera, + INT* piIspProcessor +); + +/******************************************************/ +// 函数名 : CameraSetBlackLevel +// 功能描述 : 设置图像的黑电平基准,默认值为0 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iBlackLevel 要设定的电平值。范围为0到255。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetBlackLevel( + CameraHandle hCamera, + INT iBlackLevel +); + +/******************************************************/ +// 函数名 : CameraGetBlackLevel +// 功能描述 : 获得图像的黑电平基准,默认值为0 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piBlackLevel 返回当前的黑电平值。范围为0到255。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetBlackLevel( + CameraHandle hCamera, + INT* piBlackLevel +); + +/******************************************************/ +// 函数名 : CameraSetWhiteLevel +// 功能描述 : 设置图像的白电平基准,默认值为255 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// iWhiteLevel 要设定的电平值。范围为0到255。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetWhiteLevel( + CameraHandle hCamera, + INT iWhiteLevel +); + +/******************************************************/ +// 函数名 : CameraGetWhiteLevel +// 功能描述 : 获得图像的白电平基准,默认值为255 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// piWhiteLevel 返回当前的白电平值。范围为0到255。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetWhiteLevel( + CameraHandle hCamera, + INT* piWhiteLevel +); + +/******************************************************/ +// 函数名 : CameraSetIspOutFormat +// 功能描述 : 设置CameraGetImageBuffer函数的图像处理的输出格式,支持 +// CAMERA_MEDIA_TYPE_MONO8和CAMERA_MEDIA_TYPE_RGB8 +// (在CameraDefine.h中定义)三种,分别对应8位灰度图像和24位彩色图像。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// uFormat 要设定格式。CAMERA_MEDIA_TYPE_MONO8或者CAMERA_MEDIA_TYPE_RGB8 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraSetIspOutFormat( + CameraHandle hCamera, + UINT uFormat +); + +/******************************************************/ +// 函数名 : CameraGetIspOutFormat +// 功能描述 : 获得图像处理的输出格式,目前只支持 +// CAMERA_MEDIA_TYPE_MONO8和CAMERA_MEDIA_TYPE_RGB8 +// (在CameraDefine.h中定义)两种,其他的参数会返回错误。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// puFormat 返回当前设定的格式。CAMERA_MEDIA_TYPE_MONO8或者CAMERA_MEDIA_TYPE_RGB8 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetIspOutFormat( + CameraHandle hCamera, + UINT* puFormat +); + +/******************************************************/ +// 函数名 : CameraGetErrorString +// 功能描述 : 获得错误码对应的描述字符串 +// 参数 : iStatusCode 错误码。(定义于CameraStatus.h中) +// 返回值 : 成功时,返回错误码对应的字符串首地址; +// 否则返回NULL。 +/******************************************************/ +MVSDK_API char* CameraGetErrorString( + CameraSdkStatus iStatusCode +); + + +/******************************************************/ +// 函数名 : CameraReConnect +// 功能描述 : 重新连接设备,用于USB设备意外掉线后重连 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraReConnect( + CameraHandle hCamera +); + + +/******************************************************/ +// 函数名 : CameraConnectTest +// 功能描述 : 测试相机的连接状态,用于检测相机是否掉线 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0),表示相机连接状态正常; +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraConnectTest( + CameraHandle hCamera +); + +// 申请一段对齐的内存空间。功能和malloc类似,但是返回的内存是以align指定的字节数对齐的 +MVSDK_API BYTE* CameraAlignMalloc(int size, int align); + +//释放由CameraAlignMalloc 函数分配的内存空间。 +MVSDK_API void CameraAlignFree(BYTE* membuffer); + +/******************************************************/ +// 函数名 : CameraCommonCall +// 功能描述 : 相机的一些特殊功能调用,二次开发时一般不需要调用。 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// pszCall 功能及参数 +// pszResult 调用结果,不同的pszCall时,意义不同。 +// uResultBufSize pszResult指向的缓冲区的字节大小 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraCommonCall( + CameraHandle hCamera, + char const* pszCall, + char* pszResult, + UINT uResultBufSize +); + +/******************************************************/ +// 函数名 : CameraGetEyeCount +// 功能描述 : 获取多目相机的目数 +// 参数 : hCamera 相机的句柄,由CameraInit函数获得。 +// 返回值 : 成功时,返回CAMERA_STATUS_SUCCESS (0); +// 否则返回非0值的错误码,请参考CameraStatus.h +// 中错误码的定义。 +/******************************************************/ +MVSDK_API CameraSdkStatus CameraGetEyeCount( + CameraHandle hCamera, + int *eyecount +); + +/// @ingroup API_MULTI_EYE +/// \~chinese +/// \brief 对多目相机帧内的某个单目图做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 CameraMultiEyeImageProcess( + CameraHandle hCamera, + int iEyeIndex, + BYTE* pbyIn, + tSdkFrameHead* pInFrInfo, + BYTE* pbyOut, + tSdkFrameHead* pOutFrInfo, + UINT uOutFormat, + UINT uReserved + ); + +/// @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 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 CameraSetLightingControllerState( + CameraHandle hCamera, + int index, + int state + ); + +/// @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 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 CameraConvertFrameBufferFormat( + CameraHandle hCamera, + BYTE *pInFrameBuffer, + BYTE *pOutFrameBuffer, + int outWidth, + int outHeight, + UINT outMediaType, + tSdkFrameHead* pFrameHead + ); + +/// @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 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 CameraGetFrameTimeStamp( + CameraHandle hCamera, + UINT* TimeStampL, + UINT* TimeStampH + ); + +/// @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 CameraSetConnectionStatusCallback( + CameraHandle hCamera, + CAMERA_CONNECTION_STATUS_CALLBACK pCallBack, + PVOID pContext + ); + +/// @ingroup API_ENUM +/// \~chinese +/// \brief 从指定IP枚举GIGE设备,并建立设备列表(适用于相机和电脑不在同一网段的情况) +/// \param [in] ppIpList 目标IP +/// \param [in] numIp 目标IP个数 +/// \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 Enumerates GIGE devices from the specified IP and builds a device list (applicable when the camera and computer are not on the same network segment) +/// \param [in] ppIpList target IP +/// \param [in] numIp number of target IPs +/// \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 CameraGigeEnumerateDevice( + char const** ppIpList, + int numIp, + tSdkCameraDevInfo* pCameraList, + INT* piNums +); + +/// @ingroup API_UTIL +/// \~chinese +/// \brief 配置网口相机的一些功能选项 +/// \param [in] optionName 选项("NumBuffers", "3") +/// \param [in] value 值 +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Configure some options for the gige camera +/// \param [in] optionName option name("NumBuffers", "3") +/// \param [in] value setting 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 CameraGigeSetOption( + char const* optionName, + char const* value + ); + +/// @ingroup API_UTIL +/// \~chinese +/// \brief 获取GIGE相机的IP地址 +/// \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 CameraGigeGetIp( + tSdkCameraDevInfo* pCameraInfo, + char* CamIp, + char* CamMask, + char* CamGateWay, + char* EtIp, + char* EtMask, + char* EtGateWay + ); + +/// @ingroup API_UTIL +/// \~chinese +/// \brief 设置GIGE相机的IP地址 +/// \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: 设置相机为固定IP,FALSE:设置相机自动分配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 CameraGigeSetIp( + tSdkCameraDevInfo* pCameraInfo, + char const* Ip, + char const* SubMask, + char const* GateWay, + BOOL bPersistent + ); + +/// @ingroup API_UTIL +/// \~chinese +/// \brief 获取GIGE相机的MAC地址 +/// \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 CameraGigeGetMac( + tSdkCameraDevInfo* pCameraInfo, + char* CamMac, + char* EtMac + ); + +/// @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 CameraClearBuffer( + CameraHandle hCamera + ); + +/// @ingroup API_GRAB +/// \~chinese +/// \brief 获得一帧图像数据。 +/// \param [in] hCamera 相机的句柄。 +/// \param [out] pFrameInfo 图像的帧头信息指针。 +/// \param [out] pbyBuffer 指向图像的数据的缓冲区指针。 +/// \param [in] wTimes 抓取图像的超时时间。 +/// \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 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 抓取图像的超时时间。单位毫秒。 +/// \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* CameraGetImageBufferPriorityEx( + CameraHandle hCamera, + INT* piWidth, + INT* piHeight, + UINT wTimes, + UINT Priority + ); + +/// @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 CameraSoftTriggerEx( + CameraHandle hCamera, + UINT uFlags + ); + +/// @ingroup API_ADVANCE +/// \~chinese +/// \brief 当相机处于触发模式(软触发或硬触发)时,相机发送一帧到PC,如相机未收到PC端的接收确认,相机可以把帧重发几次。用本函数设置相机重发次数。(仅网口相机支持) +/// \param [in] hCamera 相机的句柄。 +/// \param [in] count 重发次数(<=0表示禁用重发功能) +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief When the camera is in the trigger mode (soft trigger or hard trigger), the camera sends a frame to the PC. If the camera does not receive the reception confirmation from the PC, the camera can retransmit the frame several times. Use this function to set the number of camera resends. (only supported by Gige camera) +/// \param [in] hCamera Camera handle. +/// \param [in] count number of resends (<=0 means disable resends) +/// \return Returns CAMERA_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 CameraSetFrameResendCount( + CameraHandle hCamera, + int count + ); + +/// @ingroup API_BASIC +/// \~chinese +/// \brief 配置系统选项(通常需要在CameraInit打开相机之前配置好) +/// \param [in] optionName 选项("NumBuffers", "3") +/// \param [in] value 值 +/// \return 成功返回 CAMERA_STATUS_SUCCESS(0)。否则返回非0值的错误码, 请参考 CameraStatus.h 中错误码的定义。 +/// \~english +/// \brief Configure system options (usually required before CameraInit turns on the camera) +/// \param [in] optionName option name("NumBuffers", "3") +/// \param [in] value setting 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 CameraSetSysOption( + char const* optionName, + char const* value + ); + +#ifdef __cplusplus +} +#endif +#endif + diff --git a/roborts_camera/mvc/CameraDefine.h b/roborts_camera/mvc/CameraDefine.h new file mode 100644 index 00000000..6b3ca1cb --- /dev/null +++ b/roborts_camera/mvc/CameraDefine.h @@ -0,0 +1,771 @@ +#pragma once +#ifndef _CAMERA_DEFINE_H_ +#define _CAMERA_DEFINE_H_ + +#include "CameraStatus.h" + +#define MAX_CROSS_LINE 9 + +//ľͶ +typedef int CameraHandle; +typedef int INT; +typedef int LONG; +typedef unsigned int UINT; +typedef unsigned long long UINT64; +typedef int BOOL; +typedef unsigned char BYTE; +typedef unsigned int DWORD; +typedef void* PVOID; +typedef void* HWND; +typedef char* LPCTSTR; +typedef unsigned short USHORT; +typedef short SHORT; + typedef unsigned char* LPBYTE; +typedef char CHAR; +typedef char TCHAR; +typedef unsigned short WORD; +typedef INT HANDLE; +typedef void VOID; +typedef unsigned int ULONG; +typedef void* LPVOID; +typedef unsigned char UCHAR; +typedef void* HMODULE; + +#define TRUE 1 +#define FALSE 0 +//ͼ任ķʽ +typedef enum +{ + LUTMODE_PARAM_GEN=0,//ͨڲ̬LUT + LUTMODE_PRESET, //ʹԤLUT + LUTMODE_USER_DEF //ʹûԶLUT +}emSdkLutMode; + +//Ƶ +typedef enum +{ + RUNMODE_PLAY=0, //Ԥͼʾڴģʽȴ֡ĵ + RUNMODE_PAUSE, //ͣͣͼͬʱҲȥͼ + RUNMODE_STOP //ֹͣʼʹֹͣģʽ +}emSdkRunMode; + +//SDKڲʾӿڵʾʽ +typedef enum +{ + DISPLAYMODE_SCALE=0, //ʾģʽŵʾؼijߴ + DISPLAYMODE_REAL //1:1ʾģʽͼߴʾؼijߴʱֻʾֲ +}emSdkDisplayMode; + +//¼״̬ +typedef enum +{ + RECORD_STOP = 0, //ֹͣ + RECORD_START, //¼ + RECORD_PAUSE //ͣ +}emSdkRecordMode; + +//ͼľ +typedef enum +{ + MIRROR_DIRECTION_HORIZONTAL = 0,//ˮƽ + MIRROR_DIRECTION_VERTICAL //ֱ +}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; + +//Ƶ֡ +typedef enum +{ + FRAME_SPEED_LOW = 0, //ģʽ + FRAME_SPEED_NORMAL, //ͨģʽ + FRAME_SPEED_HIGH, //ģʽ(ҪϸߵĴ,豸ʱ֡ʵȶӰ) + FRAME_SPEED_SUPER //ģʽ(ҪϸߵĴ,豸ʱ֡ʵȶӰ) +}emSdkFrameSpeed; + +//ļĸʽ +typedef enum +{ + FILE_JPG = 1,//JPG + FILE_BMP = 2,//BMP + FILE_RAW = 4,//bayerʽļ,ڲ֧bayerʽ޷Ϊøʽ + FILE_PNG = 8, //PNG + 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; + +//еͼ񴫸Ĺģʽ +typedef enum +{ + CONTINUATION = 0,//ɼģʽ + SOFT_TRIGGER, //ģʽָ󣬴ʼɼָ֡ͼ񣬲ɼɺֹͣ + EXTERNAL_TRIGGER //Ӳģʽյⲿźţʼɼָ֡ͼ񣬲ɼɺֹͣ +} emSdkSnapMode; + +//ԶعʱƵƵ +typedef enum +{ + LIGHT_FREQUENCY_50HZ = 0,//50HZ,һĵƹⶼ50HZ + LIGHT_FREQUENCY_60HZ //60HZ,Ҫָʾ +}emSdkLightFrequency; + +//òΪA,B,C,D 4б档 +typedef enum +{ + PARAMETER_TEAM_DEFAULT = 0xff, + PARAMETER_TEAM_A = 0, + PARAMETER_TEAM_B = 1, + PARAMETER_TEAM_C = 2, + PARAMETER_TEAM_D = 3 +}emSdkParameterTeam; + + +/*emSdkParameterMode ģʽطΪļʹ豸ַʽ + +PARAM_MODE_BY_MODEL:ͬͺŵABCDļ޸ + һ̨IJļӰ쵽ͬͺŵ + ء + +PARAM_MODE_BY_NAME:豸ͬABCDļ + Ĭ£ֻijͺһ̨ʱ + 豸һģϣijһ̨ܹ + ͬIJļͨ޸豸ķʽ + ָIJļ + +PARAM_MODE_BY_SN:ԼΨһкABCDļ + кڳʱѾ̻ڣÿ̨к + ַͬͨʽÿ̨IJļǶġ + +ԸԼʹûʹϼַʽز磬 +MV-U300Ϊϣ̨ͺŵ ϶4ô +ʹPARAM_MODE_BY_MODELʽ;ϣijһ̨ij̨MV-U300 +ʹԼļMV-U300ҪʹͬIJļôʹ +PARAM_MODE_BY_NAMEʽ;ϣÿ̨MV-U300ʹòͬIJļô +ʹPARAM_MODE_BY_SNʽ +ļڰװĿ¼ \Camera\Configs Ŀ¼£configΪ׺ļ +*/ +typedef enum +{ + PARAM_MODE_BY_MODEL = 0, //ͺļмزMV-U300 + PARAM_MODE_BY_NAME, //豸dz(tSdkCameraDevInfo.acFriendlyName)ļмزMV-U300,dzƿԶ + PARAM_MODE_BY_SN, //豸ΨһкŴļмزкڳʱѾд豸ÿ̨ӵвͬкš + PARAM_MODE_IN_DEVICE //豸Ĺ̬洢мزеͺŶִ֧жд飬tSdkCameraCapbility.bParamInDevice +}emSdkParameterMode; + + +//SDKɵҳֵ +typedef enum +{ + PROP_SHEET_INDEX_EXPOSURE = 0, + PROP_SHEET_INDEX_ISP_COLOR, + PROP_SHEET_INDEX_ISP_LUT, + PROP_SHEET_INDEX_ISP_SHAPE, + PROP_SHEET_INDEX_VIDEO_FORMAT, + PROP_SHEET_INDEX_RESOLUTION, + PROP_SHEET_INDEX_IO_CTRL, + PROP_SHEET_INDEX_TRIGGER_SET, + PROP_SHEET_INDEX_OVERLAY, + PROP_SHEET_INDEX_DEVICE_INFO, + PROP_SHEET_INDEX_WDR, + PROP_SHEET_INDEX_MULTI_EXPOSURE +}emSdkPropSheetMask; + +//SDKɵҳĻصϢ +typedef enum +{ + SHEET_MSG_LOAD_PARAM_DEFAULT = 0, //ָĬϺ󣬴Ϣ + SHEET_MSG_LOAD_PARAM_GROUP, //ָ飬Ϣ + SHEET_MSG_LOAD_PARAM_FROMFILE, //ָļز󣬴Ϣ + SHEET_MSG_SAVE_PARAM_GROUP //ǰ鱻ʱϢ +}emSdkPropSheetMsg; + +//ӻѡοڵ +typedef enum +{ + REF_WIN_AUTO_EXPOSURE = 0, + REF_WIN_WHITE_BALANCE, +}emSdkRefWinType; + +//ӻѡοڵ +typedef enum +{ + RES_MODE_PREVIEW = 0, + RES_MODE_SNAPSHOT, +}emSdkResolutionMode; + +//ƽʱɫģʽ +typedef enum +{ + CT_MODE_AUTO = 0, //Զʶɫ + CT_MODE_PRESET, //ʹָԤɫ + CT_MODE_USER_DEF //Զɫ(;) +}emSdkClrTmpMode; + +//LUTɫͨ +typedef enum +{ + LUT_CHANNEL_ALL = 0,//R,B,Gͨͬʱ + LUT_CHANNEL_RED, //ɫͨ + LUT_CHANNEL_GREEN, //ɫͨ + LUT_CHANNEL_BLUE, //ɫͨ +}emSdkLutChannel; + +//ISPԪ +typedef enum +{ + ISP_PROCESSSOR_PC = 0,//ʹPCISPģ + ISP_PROCESSSOR_DEVICE //ʹԴӲISPģ +}emSdkIspProcessor; + +//źſƷʽ +typedef enum +{ + STROBE_SYNC_WITH_TRIG_AUTO = 0, //ʹźͬعʱԶSTROBEźšʱЧԿ(CameraSetStrobePolarity) + STROBE_SYNC_WITH_TRIG_MANUAL, //ʹźͬSTROBEʱָʱ(CameraSetStrobeDelayTime)ٳָʱ(CameraSetStrobePulseWidth)ЧԿ(CameraSetStrobePolarity) + STROBE_ALWAYS_HIGH, //ʼΪߣSTROBEźŵ + STROBE_ALWAYS_LOW //ʼΪͣSTROBEźŵ +}emStrobeControl; + +//Ӳⴥź +typedef enum +{ + EXT_TRIG_LEADING_EDGE = 0, //شĬΪ÷ʽ + EXT_TRIG_TRAILING_EDGE, //½ش + EXT_TRIG_HIGH_LEVEL, //ߵƽ,ƽȾعʱ䣬ͺŵֵ֧ƽʽ + EXT_TRIG_LOW_LEVEL //͵ƽ, +}emExtTrigSignal; + +//ӲⴥʱĿŷʽ +typedef enum +{ + EXT_TRIG_EXP_STANDARD = 0, //׼ʽĬΪ÷ʽ + EXT_TRIG_EXP_GRR, //ȫָλʽֹŵCMOSͺŵָ֧÷ʽⲿеţԴﵽȫֿŵЧʺĸ˶ +}emExtTrigShutterMode; + +// GPIOģʽ +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 + IOMODE_ROTARYENC_INPUT=5, ///< \~chinese \~english rotary input +}emCameraGPIOMode; + +/// @ingroup MV_ENUM_TYPE +/// \~chinese GPIO ʽ +/// \~english GPIO Format +typedef enum +{ + IOFORMAT_SINGLE=0, ///< \~chinese \~english single ended + IOFORMAT_RS422=1, ///< \~chinese RS422 \~english Differential RS422 + IOFORMAT_RS422_TERM=2, ///< \~chinese RS422ն˵ \~english Differential RS422 and Termination Enable +}emCameraGPIOFormat; + +/// @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; + +//豸Ϣ +typedef struct +{ + char acProductSeries[32]; // Ʒϵ + char acProductName[32]; // Ʒ + char acFriendlyName[32]; // ƷdzƣûԶdzƣڣֶͬʱʹ,CameraSetFriendlyNameӿڸıdzƣ豸Ч + char acLinkName[32]; // ں˷ڲʹ + char acDriverVersion[32]; // 汾 + char acSensorType[32]; // sensor + char acPortType[32]; // ӿ + char acSn[32]; // ƷΨһк + UINT uInstance; // ͺڸõϵʵţͬͺŶ +} tSdkCameraDevInfo; + +#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) + +//ķֱ趨ΧڹUI +typedef struct +{ + INT iHeightMax; //ͼ߶ + INT iHeightMin; //ͼС߶ + INT iWidthMax; //ͼ + INT iWidthMin; //ͼС + UINT uSkipModeMask; //SKIPģʽ룬Ϊ0ʾ֧SKIP bit0Ϊ1,ʾ֧SKIP 2x2 ;bit1Ϊ1ʾ֧SKIP 3x3.... + UINT uBinSumModeMask; //BIN()ģʽ룬Ϊ0ʾ֧BIN bit0Ϊ1,ʾ֧BIN 2x2 ;bit1Ϊ1ʾ֧BIN 3x3.... + UINT uBinAverageModeMask; //BIN(ֵ)ģʽ룬Ϊ0ʾ֧BIN bit0Ϊ1,ʾ֧BIN 2x2 ;bit1Ϊ1ʾ֧BIN 3x3.... + UINT uResampleMask; //Ӳز +} tSdkResolutionRange; + + +//ķֱ +typedef struct +{ + INT iIndex; // ţ[0,N]ʾԤķֱ(N ΪԤֱʵһ㲻20),OXFF ʾԶֱ(ROI) + char acDescription[32]; // ÷ֱʵϢԤֱʱϢЧԶֱʿɺԸϢ + UINT uBinSumMode; // BIN()ģʽ,ΧܳtSdkResolutionRangeuBinSumModeMask + UINT uBinAverageMode; // BIN(ֵ)ģʽ,ΧܳtSdkResolutionRangeuBinAverageModeMask + UINT uSkipMode; // ǷSKIPijߴ磬Ϊ0ʾֹSKIPģʽΧܳtSdkResolutionRangeuSkipModeMask + UINT uResampleMask; // Ӳز + INT iHOffsetFOV; // ɼӳSensorӳϽǵĴֱƫ + INT iVOffsetFOV; // ɼӳSensorӳϽǵˮƽƫ + INT iWidthFOV; // ɼӳĿ + INT iHeightFOV; // ɼӳĸ߶ + INT iWidth; // ͼĿ + INT iHeight; // ͼĸ߶ + INT iWidthZoomHd; // ӲŵĿ,Ҫд˲ķֱʣ˱Ϊ0. + INT iHeightZoomHd; // Ӳŵĸ߶,Ҫд˲ķֱʣ˱Ϊ0. + INT iWidthZoomSw; // ŵĿ,Ҫд˲ķֱʣ˱Ϊ0. + INT iHeightZoomSw; // ŵĸ߶,Ҫд˲ķֱʣ˱Ϊ0. +} tSdkImageResolution; + +//ƽɫģʽϢ +typedef struct +{ + INT iIndex; // ģʽ + char acDescription[32]; // Ϣ +} tSdkColorTemperatureDes; + +//֡Ϣ +typedef struct +{ + INT iIndex; // ֡ţһ0Ӧڵģʽ1Ӧͨģʽ2Ӧڸģʽ + char acDescription[32]; // Ϣ +} tSdkFrameSpeed; + +//ع⹦ܷΧ +typedef struct +{ + UINT uiTargetMin; //ԶعĿСֵ + UINT uiTargetMax; //ԶعĿֵ + UINT uiAnalogGainMin; //ģСֵλΪfAnalogGainStepж + UINT uiAnalogGainMax; //ģֵλΪfAnalogGainStepж + float fAnalogGainStep; //ģÿ1ӦӵķŴ磬uiAnalogGainMinһΪ16fAnalogGainStepһΪ0.125ôСŴ16*0.125 = 2 + UINT uiExposeTimeMin; //ֶģʽ£عʱСֵλ:СCameraGetExposureLineTimeԻһжӦʱ(΢),Ӷõ֡عʱ + UINT uiExposeTimeMax; //ֶģʽ£عʱֵλ: +} tSdkExpose; + +//ģʽ +typedef struct +{ + INT iIndex; //ģʽ + char acDescription[32]; //ģʽϢ +} tSdkTrigger; + +//ְС(ҪЧ) +typedef struct +{ + INT iIndex; //ְС + char acDescription[32]; //ӦϢ + UINT iPackSize; +} tSdkPackLength; + +//ԤLUT +typedef struct +{ + INT iIndex; // + char acDescription[32]; //Ϣ +} tSdkPresetLut; + +//AE㷨 +typedef struct +{ + INT iIndex; // + char acDescription[32]; //Ϣ +} tSdkAeAlgorithm; + +//RAWתRGB㷨 +typedef struct +{ + INT iIndex; // + char acDescription[32]; //Ϣ +} tSdkBayerDecodeAlgorithm; + + +//֡ͳϢ +typedef struct +{ + INT iTotal; //ǰɼ֡֡ + INT iCapture; //ǰɼЧ֡ + INT iLost; //ǰ֡ +} tSdkFrameStatistic; + +//ͼݸʽ +typedef struct +{ + INT iIndex; //ʽ + char acDescription[32]; //Ϣ + UINT iMediaType; //Ӧͼʽ룬CAMERA_MEDIA_TYPE_BAYGR8ڱļж塣 +} tSdkMediaType; + +//٤趨Χ +typedef struct +{ + INT iMin; //Сֵ + INT iMax; //ֵ +} tGammaRange; + +//Աȶȵ趨Χ +typedef struct +{ + INT iMin; //Сֵ + INT iMax; //ֵ +} tContrastRange; + +//RGBͨ趨Χ +typedef struct +{ + INT iRGainMin; //ɫСֵ + INT iRGainMax; //ɫֵ + INT iGGainMin; //ɫСֵ + INT iGGainMax; //ɫֵ + INT iBGainMin; //ɫСֵ + INT iBGainMax; //ɫֵ +} tRgbGainRange; + +//Ͷ趨ķΧ +typedef struct +{ + INT iMin; //Сֵ + INT iMax; //ֵ +} tSaturationRange; + +//񻯵趨Χ +typedef struct +{ + INT iMin; //Сֵ + INT iMax; //ֵ +} tSharpnessRange; + +//ISPģʹϢ +typedef struct +{ + BOOL bMonoSensor; //ʾͺǷΪڰ,ǺڰɫصĹܶ޷ + BOOL bWbOnce; //ʾͺǷֶ֧ƽ⹦ + BOOL bAutoWb; //ʾͺǷ֧Զƽ⹦ + BOOL bAutoExposure; //ʾͺǷ֧Զع⹦ + BOOL bManualExposure; //ʾͺǷֶ֧ع⹦ + BOOL bAntiFlick; //ʾͺǷֿ֧Ƶ + BOOL bDeviceIsp; //ʾͺǷ֧ӲISP + BOOL bForceUseDeviceIsp;//bDeviceIspbForceUseDeviceIspͬʱΪTRUEʱʾǿֻӲISPȡ + BOOL bZoomHD; //ӲǷ֧ͼ(ֻС) +} tSdkIspCapacity; + +/* ϵ豸ϢЩϢڶ̬UI */ +typedef struct +{ + + tSdkTrigger *pTriggerDesc; // ģʽ + INT iTriggerDesc; // ģʽĸpTriggerDescĴС + + tSdkImageResolution *pImageSizeDesc;// Ԥֱѡ + INT iImageSizeDesc; // ԤֱʵĸpImageSizeDescĴС + + tSdkColorTemperatureDes *pClrTempDesc;// Ԥɫģʽڰƽ + INT iClrTempDesc; + + tSdkMediaType *pMediaTypeDesc; // ͼʽ + INT iMediaTypdeDesc; // ͼʽpMediaTypeDescĴС + + tSdkFrameSpeed *pFrameSpeedDesc; // ɵ֡ͣӦͨ ͳٶ + INT iFrameSpeedDesc; // ɵ֡͵ĸpFrameSpeedDescĴС + + tSdkPackLength *pPackLenDesc; // ȣһ豸 + INT iPackLenDesc; // ɹѡĴְȵĸpPackLenDescĴС + + INT iOutputIoCounts; // ɱIOĸ + INT iInputIoCounts; // ɱIOĸ + + tSdkPresetLut *pPresetLutDesc; // ԤLUT + INT iPresetLut; // ԤLUTĸpPresetLutDescĴС + + INT iUserDataMaxLen; // ָʾڱû󳤶ȡΪ0ʾޡ + BOOL bParamInDevice; // ָʾ豸Ƿִ֧豸жд顣1Ϊ֧֣0֧֡ + + tSdkAeAlgorithm *pAeAlmSwDesc; // Զع㷨 + int iAeAlmSwDesc; // Զع㷨 + + tSdkAeAlgorithm *pAeAlmHdDesc; // ӲԶع㷨ΪNULLʾ֧ӲԶع + int iAeAlmHdDesc; // ӲԶع㷨Ϊ0ʾ֧ӲԶع + + tSdkBayerDecodeAlgorithm *pBayerDecAlmSwDesc; // BayerתΪRGBݵ㷨 + int iBayerDecAlmSwDesc; // BayerתΪRGBݵ㷨 + + tSdkBayerDecodeAlgorithm *pBayerDecAlmHdDesc; // ӲBayerתΪRGBݵ㷨ΪNULLʾ֧ + int iBayerDecAlmHdDesc; // ӲBayerתΪRGBݵ㷨Ϊ0ʾ֧ + + /* ͼĵڷΧ,ڶ̬UI*/ + tSdkExpose sExposeDesc; // عķΧֵ + tSdkResolutionRange sResolutionRange; // ֱʷΧ + tRgbGainRange sRgbGainRange; // ͼ淶Χ + tSaturationRange sSaturationRange; // ͶȷΧ + tGammaRange sGammaRange; // ٤Χ + tContrastRange sContrastRange; // ԱȶȷΧ + tSharpnessRange sSharpnessRange; // 񻯷Χ + tSdkIspCapacity sIspCapacity; // ISP + + +} tSdkCameraCapbility; + + +//ͼ֡ͷϢ +typedef struct +{ + UINT uiMediaType; // ͼʽ,Image Format + UINT uBytes; // ͼֽ,Total bytes + INT iWidth; // ͼĿȣͼ󣬸ñܱ̬޸ģָʾͼߴ + INT iHeight; // ͼĸ߶ȣͼ󣬸ñܱ̬޸ģָʾͼߴ + INT iWidthZoomSw; // ŵĿ,Ҫüͼ񣬴˱Ϊ0. + INT iHeightZoomSw; // ŵĸ߶,Ҫüͼ񣬴˱Ϊ0. + BOOL bIsTrigger; // ָʾǷΪ֡ is trigger + UINT uiTimeStamp; // ֡IJɼʱ䣬λ0.1 + UINT uiExpTime; // ǰͼعֵλΪ΢us + float fAnalogGain; // ǰͼģ汶 + INT iGamma; // ֡ͼ٤趨ֵLUTģʽΪ̬ʱЧģʽΪ-1 + INT iContrast; // ֡ͼĶԱȶ趨ֵLUTģʽΪ̬ʱЧģʽΪ-1 + INT iSaturation; // ֡ͼıͶ趨ֵںڰ壬Ϊ0 + float fRgain; // ֡ͼĺɫ汶ںڰ壬Ϊ1 + float fGgain; // ֡ͼɫ汶ںڰ壬Ϊ1 + float fBgain; // ֡ͼɫ汶ںڰ壬Ϊ1 +}tSdkFrameHead; + +//ͼ֡ +typedef struct sCameraFrame +{ + tSdkFrameHead head; //֡ͷ + BYTE * pBuffer; // +}tSdkFrame; + +//ͼ񲶻Ļص +typedef void (*CAMERA_SNAP_PROC)(CameraHandle hCamera, BYTE *pFrameBuffer, tSdkFrameHead* pFrameHead,PVOID pContext); + +//SDKɵҳϢص +typedef void (*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 (*CAMERA_CONNECTION_STATUS_CALLBACK)(CameraHandle hCamera,UINT MSG,UINT uParam,PVOID pContext); + + +//----------------------------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/roborts_camera/mvc/CameraStatus.h b/roborts_camera/mvc/CameraStatus.h new file mode 100644 index 00000000..874cb847 --- /dev/null +++ b/roborts_camera/mvc/CameraStatus.h @@ -0,0 +1,110 @@ + +#ifndef __CAMERA_STATUS_DEF__ +#define __CAMERA_STATUS_DEF__ + +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;\ + } + + +/* ô */ + +#define CAMERA_STATUS_SUCCESS 0 // ɹ +#define CAMERA_STATUS_FAILED -1 // ʧ +#define CAMERA_STATUS_INTERNAL_ERROR -2 // ڲ +#define CAMERA_STATUS_UNKNOW -3 // δ֪ +#define CAMERA_STATUS_NOT_SUPPORTED -4 // ָ֧ù +#define CAMERA_STATUS_NOT_INITIALIZED -5 // ʼδ +#define CAMERA_STATUS_PARAMETER_INVALID -6 // Ч +#define CAMERA_STATUS_PARAMETER_OUT_OF_BOUND -7 // Խ +#define CAMERA_STATUS_UNENABLED -8 // δʹ +#define CAMERA_STATUS_USER_CANCEL -9 // ûֶȡˣroiȡ +#define CAMERA_STATUS_PATH_NOT_FOUND -10 // עûҵӦ· +#define CAMERA_STATUS_SIZE_DISMATCH -11 // ͼݳȺͶijߴ粻ƥ +#define CAMERA_STATUS_TIME_OUT -12 // ʱ +#define CAMERA_STATUS_IO_ERROR -13 // ӲIO +#define CAMERA_STATUS_COMM_ERROR -14 // ͨѶ +#define CAMERA_STATUS_BUS_ERROR -15 // ߴ +#define CAMERA_STATUS_NO_DEVICE_FOUND -16 // ûз豸 +#define CAMERA_STATUS_NO_LOGIC_DEVICE_FOUND -17 // δҵ߼豸 +#define CAMERA_STATUS_DEVICE_IS_OPENED -18 // 豸Ѿ +#define CAMERA_STATUS_DEVICE_IS_CLOSED -19 // 豸Ѿر +#define CAMERA_STATUS_DEVICE_VEDIO_CLOSED -20 // ûд豸Ƶ¼صĺʱƵûд򿪣طظô +#define CAMERA_STATUS_NO_MEMORY -21 // û㹻ϵͳڴ +#define CAMERA_STATUS_FILE_CREATE_FAILED -22 // ļʧ +#define CAMERA_STATUS_FILE_INVALID -23 // ļʽЧ +#define CAMERA_STATUS_WRITE_PROTECTED -24 // дд +#define CAMERA_STATUS_GRAB_FAILED -25 // ݲɼʧ +#define CAMERA_STATUS_LOST_DATA -26 // ݶʧ +#define CAMERA_STATUS_EOF_ERROR -27 // δյ֡ +#define CAMERA_STATUS_BUSY -28 // æ(һβڽ)˴βܽ +#define CAMERA_STATUS_WAIT -29 // Ҫȴ(в)ٴγtrf +#define CAMERA_STATUS_IN_PROCESS -30 // ڽУѾ +#define CAMERA_STATUS_IIC_ERROR -31 // IIC +#define CAMERA_STATUS_SPI_ERROR -32 // SPI +#define CAMERA_STATUS_USB_CONTROL_ERROR -33 // USBƴ +#define CAMERA_STATUS_USB_BULK_ERROR -34 // USB BULK +#define CAMERA_STATUS_SOCKET_INIT_ERROR -35 // 紫׼ʼʧ +#define CAMERA_STATUS_GIGE_FILTER_INIT_ERROR -36 // ں˹ʼʧܣǷȷװ°װ +#define CAMERA_STATUS_NET_SEND_ERROR -37 // ݷʹ +#define CAMERA_STATUS_DEVICE_LOST -38 // ʧȥӣⳬʱ +#define CAMERA_STATUS_DATA_RECV_LESS -39 // յֽ +#define CAMERA_STATUS_FUNCTION_LOAD_FAILED -40 // ļмسʧ +#define CAMERA_STATUS_CRITICAL_FILE_LOST -41 // ļʧ +#define CAMERA_STATUS_SENSOR_ID_DISMATCH -42 // ̼ͳƥ䣬ԭ˴Ĺ̼ +#define CAMERA_STATUS_OUT_OF_RANGE -43 // ЧΧ +#define CAMERA_STATUS_REGISTRY_ERROR -44 // װע°װ򣬻аװĿ¼Setup/Installer.exe +#define CAMERA_STATUS_ACCESS_DENY -45 // ֹʡָѾռʱʸ᷵ظ״̬(һܱͬʱ) +#define CAMERA_STATUS_CAMERA_NEED_RESET -46 // ʾҪλʹãʱϵϵͳ󣬱ʹá +#define CAMERA_STATUS_ISP_MOUDLE_NOT_INITIALIZED -47 // ISPģδʼ +#define CAMERA_STATUS_ISP_DATA_CRC_ERROR -48 // У +#define CAMERA_STATUS_MV_TEST_FAILED -49 // ݲʧ +#define CAMERA_STATUS_INTERNAL_ERR1 -50 // ڲ1 +#define CAMERA_STATUS_U3V_NO_CONTROL_EP -51 // U3Vƶ˵δҵ +#define CAMERA_STATUS_U3V_CONTROL_ERROR -52 // U3VͨѶ + + + + +//AIAƶı׼ͬ +/*#define CAMERA_AIA_SUCCESS 0x0000 */ +#define CAMERA_AIA_PACKET_RESEND 0x0100 //֡Ҫش +#define CAMERA_AIA_NOT_IMPLEMENTED 0x8001 //豸ֵ֧ +#define CAMERA_AIA_INVALID_PARAMETER 0x8002 //Ƿ +#define CAMERA_AIA_INVALID_ADDRESS 0x8003 //ɷʵĵַ +#define CAMERA_AIA_WRITE_PROTECT 0x8004 //ʵĶ󲻿д +#define CAMERA_AIA_BAD_ALIGNMENT 0x8005 //ʵĵַûаҪ +#define CAMERA_AIA_ACCESS_DENIED 0x8006 //ûзȨ +#define CAMERA_AIA_BUSY 0x8007 //ڴ +#define CAMERA_AIA_DEPRECATED 0x8008 //0x8008-0x0800B 0x800F ָѾ +#define CAMERA_AIA_PACKET_UNAVAILABLE 0x800C //Ч +#define CAMERA_AIA_DATA_OVERRUN 0x800D //ͨյݱҪĶ +#define CAMERA_AIA_INVALID_HEADER 0x800E //ݰͷijЩЭ鲻ƥ +#define CAMERA_AIA_PACKET_NOT_YET_AVAILABLE 0x8010 //ͼְݻδ׼ãڴģʽӦóʳʱ +#define CAMERA_AIA_PACKET_AND_PREV_REMOVED_FROM_MEMORY 0x8011 //ҪʵķְѾڡشʱѾڻ +#define CAMERA_AIA_PACKET_REMOVED_FROM_MEMORY 0x8012 //CAMERA_AIA_PACKET_AND_PREV_REMOVED_FROM_MEMORY +#define CAMERA_AIA_NO_REF_TIME 0x0813 //ûвοʱԴʱִͬʱ +#define CAMERA_AIA_PACKET_TEMPORARILY_UNAVAILABLE 0x0814 //ŵ⣬ǰְʱãԺз +#define CAMERA_AIA_OVERFLOW 0x0815 //豸ͨǶ +#define CAMERA_AIA_ACTION_LATE 0x0816 //ִѾЧָʱ +#define CAMERA_AIA_ERROR 0x8FFF // + + + + + +#endif diff --git a/roborts_camera/mvc/mvc_driver.cpp b/roborts_camera/mvc/mvc_driver.cpp new file mode 100644 index 00000000..af540573 --- /dev/null +++ b/roborts_camera/mvc/mvc_driver.cpp @@ -0,0 +1,65 @@ +#include +#include +#include + +#include +#include "mvc_driver.h" + + +namespace roborts_camera{ + MVCDriver::MVCDriver(CameraInfo camera_info): // The purpose of using Camera Info is just format work + CameraBase(camera_info){ // Invoke Father class's constructor + CameraSdkInit(1); + iStatus = CameraEnumerateDevice(&tCameraEnumList, &iCameraCounts); + std::cout<<"state = "< + +#include "ros/ros.h" +#include "opencv2/opencv.hpp" +#include "actionlib/server/simple_action_server.h" + +#include "../camera_param.h" +#include "../camera_base.h" +#include "alg_factory/algorithm_factory.h" +#include "CameraApi.h" + +#include "io/io.h" + +namespace roborts_camera { + class MVCDriver: public CameraBase{ + public: + explicit MVCDriver(CameraInfo camera_info); + void StartReadCamera(cv::Mat &img) override; + void StopReadCamera(); + ~MVCDriver() override; + private: + bool read_camera_initialized_; + unsigned char *g_pRgbBuffer; + int iCameraCounts = 1; + int iStatus = -1; + tSdkCameraDevInfo tCameraEnumList; + int hCamera; + tSdkCameraCapbility tCapability; + tSdkFrameHead sFrameInfo; + BYTE* pbyBuffer; + int iDisplayFrames = 10000; + IplImage *iplImage = NULL; + int channel = 3; + }; + roborts_common::REGISTER_ALGORITHM(CameraBase,"mvc",MVCDriver,CameraInfo); +} +#endif \ No newline at end of file diff --git a/roborts_camera/proto/camera_param.proto b/roborts_camera/proto/camera_param.proto index ac5e73ce..2ab904dc 100755 --- a/roborts_camera/proto/camera_param.proto +++ b/roborts_camera/proto/camera_param.proto @@ -29,13 +29,14 @@ message Camera { optional bool auto_exposure = 8; //1 open, 0 close optional uint32 exposure_value = 9; - optional uint32 exposure_time = 10;//us + optional double exposure_time = 10;//us optional bool auto_white_balance = 11; //1 open, 0 close optional bool auto_gain = 12;////1 open, 0 close - - optional uint32 contrast = 13; + optional uint32 gamma = 13; + optional uint32 contrast = 14; + optional uint32 gain = 15; } message Cameras { diff --git a/roborts_camera/test/image_capture.cpp b/roborts_camera/test/image_capture.cpp index 5d44e199..c6888b8a 100644 --- a/roborts_camera/test/image_capture.cpp +++ b/roborts_camera/test/image_capture.cpp @@ -25,7 +25,7 @@ #include "cv_bridge/cv_bridge.h" std::string topic_name = "back_camera"; -cv::VideoWriter writer(topic_name+".avi", CV_FOURCC('M', 'J', 'P', 'G'), 25.0, cv::Size(640, 360)); +cv::VideoWriter writer(topic_name+".avi",CV_FOURCC('M', 'J', 'P', 'G'), 25.0, cv::Size(640, 360)); cv::Mat src_img; void ReceiveImg(const sensor_msgs::ImageConstPtr &msg) { diff --git a/roborts_camera/uvc/uvc_driver.cpp b/roborts_camera/uvc/uvc_driver.cpp index b75a82b3..71290cff 100755 --- a/roborts_camera/uvc/uvc_driver.cpp +++ b/roborts_camera/uvc/uvc_driver.cpp @@ -19,6 +19,8 @@ #include #include +#include + #include #include "uvc_driver.h" @@ -32,6 +34,7 @@ void UVCDriver::StartReadCamera(cv::Mat &img) { if(!camera_initialized_){ camera_info_.cap_handle.open(camera_info_.camera_path); SetCameraExposure(camera_info_.camera_path, camera_info_.exposure_value); + camera_info_.cap_handle.set(cv::CAP_PROP_FPS, camera_info_.fps); ROS_ASSERT_MSG(camera_info_.cap_handle.isOpened(), "Cannot open %s .", cameras_[camera_num].video_path.c_str()); camera_initialized_ = true; } @@ -50,7 +53,7 @@ void UVCDriver::SetCameraExposure(std::string id, int val) if ((cam_fd = open(id.c_str(), O_RDWR)) == -1) { std::cerr << "Camera open error" << std::endl; } - + struct v4l2_control control_s; control_s.id = V4L2_CID_AUTO_WHITE_BALANCE; control_s.value = camera_info_.auto_white_balance; @@ -65,6 +68,8 @@ void UVCDriver::SetCameraExposure(std::string id, int val) control_s.value = val; ioctl(cam_fd, VIDIOC_S_CTRL, &control_s); close(cam_fd); + + } UVCDriver::~UVCDriver() { diff --git a/roborts_costmap/config/obstacle_layer_config.prototxt b/roborts_costmap/config/obstacle_layer_config.prototxt index fd6a04f0..bdc09c2c 100755 --- a/roborts_costmap/config/obstacle_layer_config.prototxt +++ b/roborts_costmap/config/obstacle_layer_config.prototxt @@ -13,4 +13,44 @@ footprint_clearing_enabled: false marking: true is_debug: true +zone { + start_x: 0.23 + start_y: 2.55 + end_x: 0.77 + end_y: 3.03 +} +zone { + start_x: 1.63 + start_y: 1.41 + end_x: 2.17 + end_y: 1.89 +} + +zone { + start_x: 3.77 + start_y: 3.795 + end_x: 4.31 + end_y: 4.275 +} + +zone { + start_x: 0.23 + start_y: 2.55 + end_x: 0.77 + end_y: 3.03 +} + +zone { + start_x: 1.63 + start_y: 1.41 + end_x: 2.17 + end_y: 1.89 +} + +zone { + start_x: 3.77 + start_y: 3.795 + end_x: 4.31 + end_y: 4.275 +} \ No newline at end of file diff --git a/roborts_costmap/include/costmap/obstacle_layer.h b/roborts_costmap/include/costmap/obstacle_layer.h index cc7a17a3..83d11ddc 100755 --- a/roborts_costmap/include/costmap/obstacle_layer.h +++ b/roborts_costmap/include/costmap/obstacle_layer.h @@ -69,8 +69,22 @@ #include "observation_buffer.h" #include "map_common.h" +#include "std_msgs/Int32MultiArray.h" +#include "std_msgs/MultiArrayLayout.h" +#include "std_msgs/MultiArrayDimension.h" + + namespace roborts_costmap { +class Bufferzone +{ + public: + float start_x; + float start_y; + float end_x; + float end_y; +}; + class ObstacleLayer : public CostmapLayer { public: ObstacleLayer() { @@ -89,6 +103,7 @@ class ObstacleLayer : public CostmapLayer { const std::shared_ptr &buffer); void LaserScanValidInfoCallback(const sensor_msgs::LaserScanConstPtr &message, const std::shared_ptr &buffer); + void RefereeCallback(const std_msgs::Int32MultiArray::ConstPtr &bufzones_msg); protected: bool GetMarkingObservations(std::vector &marking_observations) const; @@ -99,6 +114,8 @@ class ObstacleLayer : public CostmapLayer { double *max_x, double *max_y); void UpdateFootprint(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y); + bool SetOccupied(int zone_index); + bool SetFree(int zone_index); bool footprint_clearing_enabled_, rolling_window_; int combination_method_; std::string global_frame_; @@ -114,6 +131,8 @@ class ObstacleLayer : public CostmapLayer { std::vector static_clearing_observations_, static_marking_observations_; std::chrono::system_clock::time_point reset_time_; + char active_barrier[6] = {3,3,3,3,3,3}; // Init to be all threes : Invalid value + Bufferzone bufferzones[6]; }; } //namespace roborts_costmap diff --git a/roborts_costmap/proto/obstacle_layer_setting.proto b/roborts_costmap/proto/obstacle_layer_setting.proto index e45f0dfb..2c57efe3 100755 --- a/roborts_costmap/proto/obstacle_layer_setting.proto +++ b/roborts_costmap/proto/obstacle_layer_setting.proto @@ -15,4 +15,12 @@ message ParaObstacleLayer { required bool marking = 12; required bool footprint_clearing_enabled = 13; required bool is_debug = 14; + repeated bufzone zone = 15; +} + +message bufzone { + required float start_x = 1; + required float start_y = 2; + required float end_x = 3; + required float end_y = 4; } diff --git a/roborts_costmap/src/costmap_layer.cpp b/roborts_costmap/src/costmap_layer.cpp index fb1cc7d5..f0d2a9b1 100755 --- a/roborts_costmap/src/costmap_layer.cpp +++ b/roborts_costmap/src/costmap_layer.cpp @@ -97,7 +97,7 @@ void CostmapLayer::UpdateOverwriteByMax(Costmap2D &master_grid, int min_i, int m unsigned int span = master_grid.GetSizeXCell(); for (int j = min_j; j < max_j; j++) { - unsigned int it = j * span + min_i; + unsigned int it = j * span + min_i; // 2d to 1d transform for (int i = min_i; i < max_i; i++) { if (costmap_[it] == NO_INFORMATION) { it++; diff --git a/roborts_costmap/src/observation_buffer.cpp b/roborts_costmap/src/observation_buffer.cpp index 66e9bfa2..11cd68dd 100755 --- a/roborts_costmap/src/observation_buffer.cpp +++ b/roborts_costmap/src/observation_buffer.cpp @@ -120,6 +120,7 @@ bool ObservationBuffer::SetGlobalFrame(const std::string new_global_frame) return true; } +// Format convertion void ObservationBuffer::BufferCloud(const sensor_msgs::PointCloud2& cloud) { try @@ -147,7 +148,6 @@ void ObservationBuffer::BufferCloud(const pcl::PointCloud& cloud) // check whether the origin frame has been set explicitly or whether we should get it from the cloud string origin_frame = sensor_frame_ == "" ? cloud.header.frame_id : sensor_frame_; - try { // given these observations come from sensors... we'll need to store the origin pt of the sensor @@ -202,7 +202,7 @@ void ObservationBuffer::BufferCloud(const pcl::PointCloud& cloud) // if the update was successful, we want to update the last updated time last_updated_ = ros::Time::now(); - // we'll also remove any stale observations from the list + // we'll also remove any old observations from the list PurgeStaleObservations(); } diff --git a/roborts_costmap/src/obstacle_layer.cpp b/roborts_costmap/src/obstacle_layer.cpp index 20402bcd..7890f9e5 100755 --- a/roborts_costmap/src/obstacle_layer.cpp +++ b/roborts_costmap/src/obstacle_layer.cpp @@ -51,6 +51,7 @@ *********************************************************************/ #include "obstacle_layer_setting.pb.h" #include "obstacle_layer.h" +#include namespace roborts_costmap { @@ -75,6 +76,15 @@ void ObstacleLayer::OnInitialize() { std::string topic_string = "LaserScan", sensor_frame = "laser_frame"; topic_string = para_obstacle.topic_string(); sensor_frame = para_obstacle.sensor_frame(); + for(int i=0;i<6;i++) + { + bufferzones[i].start_x = para_obstacle.zone(i).start_x(); + bufferzones[i].start_y = para_obstacle.zone(i).start_y(); + bufferzones[i].end_x = para_obstacle.zone(i).end_x(); + bufferzones[i].end_y = para_obstacle.zone(i).end_y(); + } + + bool inf_is_valid = false, clearing = false, marking = true; inf_is_valid = para_obstacle.inf_is_valid(); @@ -169,6 +179,16 @@ void ObstacleLayer::LaserScanValidInfoCallback(const sensor_msgs::LaserScanConst buffer->Unlock(); } +void ObstacleLayer::RefereeCallback(const std_msgs::Int32MultiArray::ConstPtr &array) +{ + int i =0; + for(std::vector::const_iterator it = array->data.begin(); it != array->data.end(); ++it) + { + active_barrier[i] = *it; + i++; + } +} + void ObstacleLayer::UpdateBounds(double robot_x, double robot_y, double robot_yaw, @@ -230,6 +250,17 @@ void ObstacleLayer::UpdateBounds(double robot_x, Touch(px, py, min_x, min_y, max_x, max_y); } } + for(int i =0;i<6;i++) + { + if(active_barrier[i]==1) + { + SetOccupied(i); + } + else if(active_barrier==0) + { + SetFree(i); + } + } UpdateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y); } @@ -253,6 +284,17 @@ void ObstacleLayer::UpdateCosts(Costmap2D &master_grid, int min_i, int min_j, in default: // Nothing break; } + unsigned int min_x,min_y,max_x,max_y; + bool checker = false; + for (int i = 0;i<6;i++) + { + checker = checker || World2Map(bufferzones[i].start_x,bufferzones[i].start_y,min_x,min_y); + checker = checker && World2Map(bufferzones[i].end_x,bufferzones[i].end_y,max_x,max_y); + if(checker) + { + UpdateOverwriteByValid(master_grid,min_x,min_y,max_x,max_y); + } + } } void ObstacleLayer::Activate() { @@ -414,4 +456,50 @@ void ObstacleLayer::UpdateFootprint(double robot_x, } } +bool ObstacleLayer::SetOccupied(int zone_index) +{ + unsigned int min_x, min_y, max_x, max_y; + if(!World2Map(bufferzones[zone_index].start_x,bufferzones[zone_index].start_y,min_x,min_y)) + { + return false; + } + if(!World2Map(bufferzones[zone_index].end_x,bufferzones[zone_index].end_y,max_x,max_y)) + { + return false; + } + unsigned int index = 0; + for (int x = min_x;x<=max_x;x++) + { + for (int y = min_y;y<=max_y;y++) + { + index = GetIndex(x,y); + costmap_[index] = LETHAL_OBSTACLE; + } + } + return true; +} + +bool ObstacleLayer::SetFree(int zone_index) +{ + unsigned int min_x, min_y, max_x, max_y; + if(!World2Map(bufferzones[zone_index].start_x,bufferzones[zone_index].start_y,min_x,min_y)) + { + return false; + } + if(!World2Map(bufferzones[zone_index].end_x,bufferzones[zone_index].end_y,max_x,max_y)) + { + return false; + } + unsigned int index = 0; + for (int x = min_x;x<=max_x;x++) + { + for (int y = min_y;y<=max_y;y++) + { + index = GetIndex(x,y); + costmap_[index] = FREE_SPACE; + } + } + return true; +} + } //namespace roborts_costmap \ No newline at end of file diff --git a/roborts_decision/behavior_test.cpp b/roborts_decision/behavior_test.cpp index 621ec822..1a6e035e 100644 --- a/roborts_decision/behavior_test.cpp +++ b/roborts_decision/behavior_test.cpp @@ -1,6 +1,7 @@ #include #include "executor/chassis_executor.h" +#include "executor/gimbal_executor.h" #include "example_behavior/back_boot_area_behavior.h" #include "example_behavior/escape_behavior.h" @@ -8,17 +9,47 @@ #include "example_behavior/search_behavior.h" #include "example_behavior/patrol_behavior.h" #include "example_behavior/goal_behavior.h" +#include "blackboard/blackboard.h" +#include "std_msgs/String.h" +#include "behavior_tree/behavior_state.h" +#include "proto/decision.pb.h" +#include +#include void Command(); -char command = '0'; +void GimbalTask(); // A thread with high frequency +void goalrccallback(const geometry_msgs::Pose::ConstPtr& msg); +void twistrccallback(const geometry_msgs::Twist::ConstPtr& msg); +void omegarccallback(const roborts_msgs::TwistAccel::ConstPtr& msg); +void gimbalModeCallBack(const std_msgs::String::ConstPtr& msg); + +bool enable_flag = false; +char command = '0'; +std::string gimbal_mode = "IDLE"; +geometry_msgs::PoseStamped nextGoal; +geometry_msgs::Twist twist; +roborts_msgs::TwistAccel omega; +roborts_decision::ChassisExecutor *chassis_executor; +roborts_decision::GimbalExecutor *gimbal_executor; +roborts_decision::Blackboard *blackboard; +void GimbalTask(); // A thread with high frequency int main(int argc, char **argv) { ros::init(argc, argv, "behavior_test_node"); std::string full_path = ros::package::getPath("roborts_decision") + "/config/decision.prototxt"; - auto chassis_executor = new roborts_decision::ChassisExecutor; - auto blackboard = new roborts_decision::Blackboard(full_path); - + chassis_executor = new roborts_decision::ChassisExecutor(); + //gimbal_executor = new roborts_decision::GimbalExecutor(); + blackboard = new roborts_decision::Blackboard(full_path); + // Topics to be published + ros::NodeHandle n; + ros::Publisher enemy_pose = n.advertise("Decision/EnemyPose", 1000); + ros::Publisher self_pose = n.advertise("Decision/SelfPose", 1000); + ros::Publisher goal = n.advertise("Decision/Goal", 1000); + ros::Publisher is_detected= n.advertise("Decision/IsEnemy", 1000); + ros::Publisher is_newgoal = n.advertise("Decision/IsNewGoal", 1000); + ros::Publisher chassis_status = n.advertise("Actuator/Chassis", 1000); + // Topics end roborts_decision::BackBootAreaBehavior back_boot_area_behavior(chassis_executor, blackboard, full_path); roborts_decision::ChaseBehavior chase_behavior(chassis_executor, blackboard, full_path); roborts_decision::SearchBehavior search_behavior(chassis_executor, blackboard, full_path); @@ -26,41 +57,108 @@ int main(int argc, char **argv) { roborts_decision::PatrolBehavior patrol_behavior(chassis_executor, blackboard, full_path); roborts_decision::GoalBehavior goal_behavior(chassis_executor, blackboard); + ros::Subscriber goalsub = n.subscribe("PyDecision/Goal", 1000, goalrccallback); + ros::Subscriber twistsub = n.subscribe("PyDecision/Twist", 1000, twistrccallback); + ros::Subscriber omegasub = n.subscribe("PyDecision/Omega", 1000, omegarccallback); + ros::Subscriber gimbalsub= n.subscribe("PyDecision/GimbalCMD", 1000, gimbalModeCallBack); auto command_thread= std::thread(Command); - ros::Rate rate(10); + auto gimbal_thread = std::thread(GimbalTask); + ros::Rate rate(30); + // This structure itself can be consider as a decision tree styled Behavior Tree structure. while(ros::ok()){ - ros::spinOnce(); + ros::spinOnce(); // Keep ros agent alive and ready to receive messages + enemy_pose.publish(blackboard->GetEnemy()); + self_pose.publish(blackboard->GetRobotMapPose()); + goal.publish(blackboard->GetGoal()); + std_msgs::String s; + std::stringstream ss; + if(blackboard->IsEnemyDetected()==true) + { + ss<<"true"; + } + else + { + ss<<"false"; + } + s.data = ss.str(); + is_detected.publish(s); + std_msgs::String s2; + std::stringstream ss2; + if(blackboard->IsNewGoal()==true) + { + ss2<<"true"; + } + else + { + ss2<<"false"; + } + s2.data = ss2.str(); + is_newgoal.publish(s2); + + std_msgs::String s3; + std::stringstream ss3; + if(chassis_executor->Update()==roborts_decision::BehaviorState::RUNNING) + { + ss3<<"RUNNING"; + } + else if(chassis_executor->Update()==roborts_decision::BehaviorState::FAILURE) + { + ss3<<"FAILURE"; + } + else if(chassis_executor->Update()==roborts_decision::BehaviorState::SUCCESS) + { + ss3<<"SUCCESS"; + } + else + { + ss3<<"IDLE"; // After cancel the task + } + + s3.data = ss3.str(); + chassis_status.publish(s3); + switch (command) { //back to boot area case '1': + enable_flag = false; back_boot_area_behavior.Run(); break; //patrol case '2': + enable_flag = false; patrol_behavior.Run(); break; //chase. case '3': + enable_flag = false; chase_behavior.Run(); break; //search case '4': + enable_flag = false; search_behavior.Run(); break; //escape. case '5': + enable_flag = false; escape_behavior.Run(); break; //goal. case '6': + enable_flag = false; goal_behavior.Run(); break; + case '7': + enable_flag =true; + break; case 27: + enable_flag = false; if (command_thread.joinable()){ command_thread.join(); } return 0; default: + enable_flag = false; break; } rate.sleep(); @@ -81,11 +179,12 @@ void Command() { << "4: search behavior" << std::endl << "5: escape behavior" << std::endl << "6: goal behavior" << std::endl + << "7: Listen to Python"< "; std::cin >> command; - if (command != '1' && command != '2' && command != '3' && command != '4' && command != '5' && command != '6' && command != 27) { + if (command != '1' && command != '2' && command != '3' && command != '4' && command != '5' && command != '6' && command != '7' && command != 27) { std::cout << "please input again!" << std::endl; std::cout << "> "; std::cin >> command; @@ -94,3 +193,151 @@ void Command() { } } +void goalrccallback(const geometry_msgs::Pose::ConstPtr& msg) +{ + nextGoal.header.frame_id = "map"; + nextGoal.pose.position.x = msg->position.x; + nextGoal.pose.position.y = msg->position.y; + nextGoal.pose.position.z = msg->position.z; + + nextGoal.pose.orientation.x = msg->orientation.x; + nextGoal.pose.orientation.y = msg->orientation.y; + nextGoal.pose.orientation.z = msg->orientation.z; + nextGoal.pose.orientation.w = msg->orientation.w; + if(enable_flag==true) + { + chassis_executor->Execute(nextGoal); + } +} + +void twistrccallback(const geometry_msgs::Twist::ConstPtr& msg) +{ + twist.linear.x = msg->linear.x; + twist.linear.y = msg->linear.y; + twist.linear.z = msg->linear.z; + + twist.angular.x = msg->angular.x; + twist.angular.y = msg->angular.y; + twist.angular.z = msg->angular.z; + if(enable_flag==true) + { + chassis_executor->Execute(twist); + } +} + +void omegarccallback(const roborts_msgs::TwistAccel::ConstPtr& msg) +{ + omega.twist.linear.x = msg->twist.linear.x; + omega.twist.linear.y = msg->twist.linear.y; + omega.twist.linear.z = msg->twist.linear.z; + + omega.twist.angular.x= msg->twist.angular.x; + omega.twist.angular.y= msg->twist.angular.y; + omega.twist.angular.z= msg->twist.angular.z; + + omega.accel.linear.x = msg->accel.linear.x; + omega.accel.linear.y = msg->accel.linear.y; + omega.accel.linear.z = msg->accel.linear.z; + + omega.accel.angular.x= msg->accel.angular.x; + omega.accel.angular.y= msg->accel.angular.y; + omega.accel.angular.z= msg->accel.angular.z; + if(enable_flag==true) + { + chassis_executor->Execute(omega); + } +} + +void gimbalModeCallBack(const std_msgs::String::ConstPtr& msg) +{ + gimbal_mode = msg->data.c_str(); +} + +void GimbalTask() +{ + roborts_msgs::GimbalAngle zero_gimbal_angle; + roborts_msgs::GimbalAngle angle_mode_angle; + // Just set abs angle w.r.t. robot + angle_mode_angle.yaw_mode = false; + angle_mode_angle.pitch_mode = false; + int current_yaw = 0; + int current_pitch = 0; + actionlib::SimpleActionClient ac("decision_node_action",true); + roborts_msgs::ArmorDetectionGoal goal; + ac.waitForServer(); + // Set Appropriate Mode + while(1) + { + // Common Things To Do + + if(gimbal_mode=="IDLE") + { + // Keep Gimbal in Init Angle + ac.cancelGoal(); // Temporary + angle_mode_angle.yaw_angle = 0; + angle_mode_angle.pitch_angle = 0; + //gimbal_executor->Execute(angle_mode_angle); + } + else if(gimbal_mode=="PATROL") + { + if(!blackboard->IsEnemyDetected()) + { + goal.command = 4; + ac.sendGoal(goal); + angle_mode_angle.yaw_angle = 90*sin(current_yaw/180*3.14159265); + angle_mode_angle.pitch_angle = 20*sin(current_pitch/180*3.14159265); + current_yaw = (current_yaw+1)%360; + current_pitch = (current_pitch+1)%360; + //gimbal_executor->Execute(angle_mode_angle); + } + else // Track and shoot enemy + { + goal.command = 1; + ac.sendGoal(goal); + } + + } + else if(gimbal_mode=="LEFT") + { + if(!blackboard->IsEnemyDetected()) + { + goal.command = 4; + ac.sendGoal(goal); + angle_mode_angle.yaw_angle = -85; + angle_mode_angle.pitch_angle = 20*sin(current_pitch/180*3.14159265); + current_yaw = (current_yaw+1)%360; + current_pitch = (current_pitch+1)%360; + //gimbal_executor->Execute(angle_mode_angle); + } + else // Track and shoot enemy + { + goal.command = 1; + ac.sendGoal(goal); + } + } + else if(gimbal_mode=="RIGHT") + { + if(!blackboard->IsEnemyDetected()) + { + goal.command = 4; + ac.sendGoal(goal); + angle_mode_angle.yaw_angle = 85; + angle_mode_angle.pitch_angle = 20*sin(current_pitch/180*3.14159265); + current_yaw = (current_yaw+1)%360; + current_pitch = (current_pitch+1)%360; + //gimbal_executor->Execute(angle_mode_angle); + } + else // Track and shoot enemy + { + goal.command = 1; + ac.sendGoal(goal); + } + } + else + { + // Code shouldn't reach here if package of string is complete. + std::cout<<"Invalid Gimbal command! Received"+ gimbal_mode; + break; + } + } +} diff --git a/roborts_decision/behavior_tree/behavior_tree.h b/roborts_decision/behavior_tree/behavior_tree.h index 0d47c65b..f602bc3b 100755 --- a/roborts_decision/behavior_tree/behavior_tree.h +++ b/roborts_decision/behavior_tree/behavior_tree.h @@ -47,7 +47,7 @@ class BehaviorTree { while (ros::ok() ) { std::chrono::steady_clock::time_point start_time = std::chrono::steady_clock::now(); - // Update the blackboard data + // Update the blackboard data how to linked to blackboard mechanism. ros::spinOnce(); ROS_INFO("Frame : %d", frame); root_node_->Run(); diff --git a/roborts_decision/blackboard/blackboard.h b/roborts_decision/blackboard/blackboard.h index cb7db78a..32d9fbea 100755 --- a/roborts_decision/blackboard/blackboard.h +++ b/roborts_decision/blackboard/blackboard.h @@ -150,6 +150,7 @@ class Blackboard { } } /*---------------------------------- Tools ------------------------------------------*/ + // Get distance between to pose double GetDistance(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2) { @@ -159,7 +160,7 @@ class Blackboard { const double dy = point1.y - point2.y; return std::sqrt(dx * dx + dy * dy); } - + // Get angle difference between two pose double GetAngle(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2) { const geometry_msgs::Quaternion quaternion1 = pose1.pose.orientation; @@ -170,6 +171,7 @@ class Blackboard { return rot1.angleShortestPath(rot2); } + // Get Robot's map position based on on going publishing ROS map server. const geometry_msgs::PoseStamped GetRobotMapPose() { UpdateRobotPose(); return robot_map_pose_; @@ -179,10 +181,12 @@ class Blackboard { return costmap_ptr_; } + // How to use cost map and char map const CostMap2D* GetCostMap2D() { return costmap_2d_; } + // const unsigned char* GetCharMap() { return charmap_; } diff --git a/roborts_decision/config/decision.prototxt b/roborts_decision/config/decision.prototxt index ae32fd59..851711be 100644 --- a/roborts_decision/config/decision.prototxt +++ b/roborts_decision/config/decision.prototxt @@ -27,8 +27,8 @@ master_bot { # icra2019 map point { - x: 6.14 - y: 4.45 + x: 5.54 + y: 3.9 z: 0 roll: 0 @@ -49,7 +49,7 @@ point { point { x: 2.49 - y: 4.64 + y: 4.00 z: 0 roll: 0 diff --git a/roborts_decision/example_behavior/chase_behavior.h b/roborts_decision/example_behavior/chase_behavior.h index a939435e..d32d8100 100644 --- a/roborts_decision/example_behavior/chase_behavior.h +++ b/roborts_decision/example_behavior/chase_behavior.h @@ -49,7 +49,7 @@ class ChaseBehavior { auto dx = chase_buffer_[(chase_count_ + 2 - 1) % 2].pose.position.x - robot_map_pose.pose.position.x; auto dy = chase_buffer_[(chase_count_ + 2 - 1) % 2].pose.position.y - robot_map_pose.pose.position.y; auto yaw = std::atan2(dy, dx); - + // Robot has been chased if (std::sqrt(std::pow(dx, 2) + std::pow(dy, 2)) >= 1.0 && std::sqrt(std::pow(dx, 2) + std::pow(dy, 2)) <= 2.0) { if (cancel_goal_) { chassis_executor_->Cancel(); diff --git a/roborts_decision/example_behavior/escape_behavior.h b/roborts_decision/example_behavior/escape_behavior.h index 43b344aa..7c445525 100644 --- a/roborts_decision/example_behavior/escape_behavior.h +++ b/roborts_decision/example_behavior/escape_behavior.h @@ -54,6 +54,7 @@ class EscapeBehavior { auto robot_map_pose = blackboard_->GetRobotMapPose(); float x_min, x_max; + // If enemy occur on left then system choose a right random position to Go that's simple... Useless if (enemy.pose.position.x < left_x_limit_) { x_min = right_random_min_x_; x_max = right_random_max_x_; diff --git a/roborts_decision/example_behavior/line_iterator.h b/roborts_decision/example_behavior/line_iterator.h index db5d8664..3e2377b5 100644 --- a/roborts_decision/example_behavior/line_iterator.h +++ b/roborts_decision/example_behavior/line_iterator.h @@ -19,6 +19,7 @@ #define ROBORTS_DECISION_LINE_ITERATOR_H #include +#include namespace roborts_decision { @@ -32,8 +33,8 @@ class FastLineIterator { , y1_( y1 ) , x_( x0 ) , y_( y0 ) - , deltax_(abs(x1 - x0)) - , deltay_(abs(y1 - y0)) + , deltax_(abs(int(x1 - x0))) + , deltay_(abs(int(y1 - y0))) , curpixel_( 0 ) { xinc1_ = (x1 - x0) >0 ?1:-1; diff --git a/roborts_decision/example_behavior/patrol_behavior.h b/roborts_decision/example_behavior/patrol_behavior.h index 3efb9719..991cfc49 100644 --- a/roborts_decision/example_behavior/patrol_behavior.h +++ b/roborts_decision/example_behavior/patrol_behavior.h @@ -29,7 +29,7 @@ class PatrolBehavior { void Run() { - auto executor_state = Update(); + auto executor_state = Update(); // Hook the leave node's status std::cout << "state: " << (int)(executor_state) << std::endl; diff --git a/roborts_decision/scripts/BT.py b/roborts_decision/scripts/BT.py new file mode 100644 index 00000000..de3d25c8 --- /dev/null +++ b/roborts_decision/scripts/BT.py @@ -0,0 +1,292 @@ +import time + +class BTNode(object): + status = ["RUNNING","SUCCESS","FAILURE","IDLE"] + def __init__(self,name): + self._name = name + self._status = "IDLE" + + def Update(self): + pass + + def OnTick(self): + pass + + def _cleanup(self): + pass + + def Reset(self): + self._status = "IDLE" + + def Cancel(self): + self.Reset() + self._cleanup() + + def __str__(self): + return self._name + + def getName(self,stack): + print(self._name) + return self._name + +class Action(BTNode): + ''' + Need to implement Update, Execute, _cleanup and override Initialization + ''' + def __init__(self,name): + self._name = name # Using Name as unique ID for explanation and visualization + + def Execute(self): + # TOBE Implemented + pass + + def Update(self): + # TOBE Implemented + return self._status + + def OnTick(self): + self.Execute() + result = self.Update() + return result + + def _cleanup(self): + # TOBE Implemented + pass + +class ConditionNode(BTNode): + status = ["SUCCESS","FAILURE","IDLE"] + def Cancel(self): + self.Reset() + + def Update(self): + # TO BE Implemented + return self._status + + def OnTick(self): + return self.Update() + +class LogicNode(BTNode): + """ + Abstract: + The result of Logic Node is Purely based on child Nodes + Need to Implement: Excecute + """ + def __init__(self,name,childs): + # A tuple Of Child Nodes + self._childs = tuple(childs) + super(LogicNode,self).__init__(name) + + def OnTick(self): + return self.Execute() + + def Execute(self): + # TO BE Implemented + pass + + def getChildNumber(self): + return len(self._childs) + + def Reset(self): + for child in self._childs: + child.Reset() + self._status = "IDLE" + + def Cancel(self): + for child in self._childs: + child.Cancel() + self.Reset() + + def getChilds(self): + return list(self._childs) + + def getName(self,stack): + print(self._name) + for child in self._childs: + print(" "*stack+"+ "), + child.getName(stack+1) + return self._name + + +class LogicFallback(LogicNode): + def Execute(self): + for child in self._childs: + childret = child.OnTick() + if childret == "SUCCESS": + self.Reset() + return childret + elif childret == "RUNNING": + return childret + elif childret == "IDLE": + raise Exception("Child Config failed! Child Name: "+str(child)+ + " Parent Name: "+self._name) + else: + continue + self.Reset() + return "FAILURE" + +class LogicFallbackMem(LogicNode): + def __init_(self,name,childs): + self._childs = tuple(childs) + super(LogicFallbackMem,self).__init__(name) + self._visited = [0]*len(childs) + + def Execute(self): + for i in range(sum(self._visited),len(self._childs)): + childret = self._childs[i].OnTick() + if childret == "SUCCESS": + self.Reset() + return childret + elif childret == "RUNNING": + return childret + elif childret == "IDLE": + raise Exception("Child Config failed! Child Name: "+str(self._childs[i])+ + " Parent Name: "+self._name) + else: + self._visited[i] = 1 + self.Reset() + return "FAILURE" + + def Reset(self): + super(LogicFallbackMem,self).Reset() + self._visited = [0]*len(self._childs) + +class LogicSequential(LogicNode): + def Execute(self): + for child in self._childs: + childret = child.OnTick() + if childret == "FAILURE": + self.Reset() + return childret + elif childret == "RUNNING": + return childret + elif childret == "IDLE": + raise Exception("Child Config failed! Child Name: "+str(child)+ + " Parent Name: "+self._name) + self.Reset() + return "SUCCESS" + +class LogicSequentialMem(LogicNode): + def __init__(self,name,childs): + self._childs = tuple(childs) + super(LogicSequentialMem,self).__init__(name) + self._visited = [0]*len(childs) + + def Execute(self): + for i in range(sum(self._visited),len(self._childs)): + childret = self._childs[i].OnTick() + if childret == "FAILURE": + self.Reset() + return childret + elif childret == "RUNNING": + return childret + elif childret == "IDLE": + raise Exception("Child Config failed! Child Name: "+str(self._childs[i])+ + " Parent Name: "+self._name) + else: + self._visited[i] = 1 + self.Reset() + return "SUCCESS" + + def Reset(self): + super(LogicSequentialMem,self).Reset() + self._visited = [0]*len(self._childs) + +class LogicParallel(LogicNode): + def __init__(self,name,childs,thresh): + super(LogicParallel,self).__init__(name,childs) + self._thresh = thresh + + def Execute(self): + rets = [] + for child in self._childs: + rets.append(child.OnTick()) + + if rets.count("SUCCESS") >= self._thresh: + self.Reset() + return "SUCCESS" + elif rets.count("FAILURE">= len(self._childs)-self._thresh): + self.Reset() + return "FAILURE" + elif rets.count("IDLE") > 0: + raise Exception("Child Config failed! Child Name: "+str(child)+ + " Parent Name: "+self._name) + else: + return "RUNNING" + +class Decorator(BTNode): + def __init__(self,name,child): + super(Decorator,self).__init__(name) + self._child = child + + def OnTick(self): + # TO BE Implemented + pass + + def Cancel(self): + self._child.Cancel() + self._status = "IDLE" + + def Reset(self): + self._child.Reset() + self._status = "IDLE" + +class InverseDecorator(Decorator): + def OnTick(self): + result = self._child.OnTick() + if result == "FAILURE": + return "SUCCESS" + elif result == "SUCCESS": + return "FAILURE" + elif result == "IDLE": + raise Exception("Child Config failed! Child Name: "+str(self._child)+ + " Parent Name: "+self._name) + else: + return "RUNNING" + +class TimedDecorator(Decorator): + def __init__(self,name,child,time): + super(TimedDecorator,self).__init__(name,child) + self._time = time + self._last_time = 0 + self._last_status = "IDLE" + + def OnTick(self): + # If Child Node return success or fail, return immediately + # If Child Node Stuck at running less than time, return running + # If Child Node Over timed; return fail. + if self._last_status == "IDLE": + self._last_time = time.time() + childret = self._child.OnTick() + if childret == "SUCCESS" or childret == "FAILURE": + self.Reset() + return childret + elif childret== "IDLE": + raise Exception("Child Config failed! Child Name: "+str(self._child)+ + " Parent Name: "+self._name) + elif time.time() - self._last_time > self._time: + self.Cancel() + return "FAILURE" + else: + self._last_status = "RUNNING" + return "RUNNING" + +class LoopDecorator(Decorator): + ''' + Make Sure there are more loop num success + ''' + def __init__(self,name,child,loop_num): + super(LoopDecorator,self).__init__(name,child) + self._loop_num = loop_num + self._counter = 0 + + def OnTick(self): + childret = self._child.OnTick() + if childret == "FAILURE": + self.Reset() + return childret + elif childret == "RUNNING": + return "RUNNING" + elif childret == "SUCCESS" and self._counter< self._loop_num: + self._counter += 1 + return "RUNNING" + diff --git a/roborts_decision/scripts/BT.pyc b/roborts_decision/scripts/BT.pyc new file mode 100644 index 00000000..f2f704b4 Binary files /dev/null and b/roborts_decision/scripts/BT.pyc differ diff --git a/roborts_decision/scripts/Blackboard.py b/roborts_decision/scripts/Blackboard.py new file mode 100644 index 00000000..20f02892 --- /dev/null +++ b/roborts_decision/scripts/Blackboard.py @@ -0,0 +1,13 @@ +import rospy +import roslib + +from std_msgs import String, Bool +from roborts_msgs import GimbalAngle, TwistAccel + +class Blackboard: + @staticmethod + def Initialize(): + ''' + Create Subscribers attached named with + On_xxx + ''' diff --git a/roborts_decision/scripts/PyConfig.py b/roborts_decision/scripts/PyConfig.py new file mode 100644 index 00000000..091d9e5e --- /dev/null +++ b/roborts_decision/scripts/PyConfig.py @@ -0,0 +1,7 @@ +# Gimbal Action Defines: + +LEFT = -90 +RIGHT = 90 +MIDDLE = 0 + +PARTROL_RATE = 1 diff --git a/roborts_decision/scripts/PyConfig.pyc b/roborts_decision/scripts/PyConfig.pyc new file mode 100644 index 00000000..24b35b06 Binary files /dev/null and b/roborts_decision/scripts/PyConfig.pyc differ diff --git a/roborts_decision/scripts/actionserver_test.py b/roborts_decision/scripts/actionserver_test.py new file mode 100644 index 00000000..01ac71ce --- /dev/null +++ b/roborts_decision/scripts/actionserver_test.py @@ -0,0 +1,22 @@ +import rospy +import roslib +import actionlib + +from roborts_msgs.msg import ArmorDetectionAction + +class TestAction(object): + def __init__(self): + self.server = actionlib.SimpleActionServer('armor_detection_node_action',ArmorDetectionAction,self.execute, False) + self.server.start() + + def execute(self,goal): + print("msg received"+str(goal.command)) + self.server.set_succeeded() + +if __name__ == "__main__": + print("Init Start") + rospy.init_node('test_server_node') + print("Init End") + server = TestAction() + print("Server Created") + rospy.spin() \ No newline at end of file diff --git a/roborts_decision/scripts/gimbal_task.py b/roborts_decision/scripts/gimbal_task.py new file mode 100644 index 00000000..02de707a --- /dev/null +++ b/roborts_decision/scripts/gimbal_task.py @@ -0,0 +1,199 @@ +import rospy +import roslib +import actionlib +import BT +import tf +from math import sin,cos,pi +import time +import PyConfig + + +from roborts_msgs.msg import GimbalAngle +from roborts_msgs.msg import ArmorDetectionAction, ArmorDetectionGoal +''' +REMARK: These Node Almost Always Return SUCCESS since it just publish messages +''' + +class GimbalPatrol(BT.Action): + # class wise static variable + zero_gimbal_angle = GimbalAngle() + def __init__(self,name): + super(GimbalPatrol,self).__init__(name) + self._cmd_gimbal_angle_pub = rospy.Publisher('cmd_gimbal_angle', GimbalAngle, queue_size=10) + self._status = "IDLE" + GimbalPatrol.zero_gimbal_angle.yaw_mode = True + GimbalPatrol.zero_gimbal_angle.pitch_mode = False + GimbalPatrol.zero_gimbal_angle.yaw_angle = PyConfig.MIDDLE + GimbalPatrol.zero_gimbal_angle.pitch_angle = 0 + self.current_yaw = 0 + self.current_pitch = 0 + self.gimbal_msg = GimbalAngle() + self.gimbal_msg.yaw_mode = True + self.gimbal_msg.pitch_mode = False + + def Execute(self): # Assume Angle here is a structure with mode, yaw,pitch and modes + try: + self.gimbal_msg.yaw_angle = 60*sin(self.current_yaw*pi/180) + self.gimbal_msg.pitch_angle = 10*sin(self.current_pitch*pi/180) + self.current_pitch = (self.current_pitch + PyConfig.PARTROL_RATE) % 360 + self.current_yaw = (self.current_yaw + PyConfig.PARTROL_RATE) % 360 + self._cmd_gimbal_angle_pub.publish(self.gimbal_msg) + except: + print("Unable to Publish") + self._status = "FAILURE" + return + self._status = "SUCCESS" + + + def Update(self): + return self._status + + def _cleanup(self): + try: + #self._cmd_gimbal_rate_pub.Publish(zero_gimbal_rate_) + self._cmd_gimbal_angle_pub.publish(PatrolAction.zero_gimbal_angle) + except: + rospy.logerr("Wrong Execution Mode") + +class GimbalLeftTurn(BT.Action): + def __init__(self,name): + super(GimbalLeftTurn,self).__init__(name) + self.cmd_publisher = rospy.Publisher("cmd_gimbal_angle",GimbalAngle,queue_size = 10) + self._status = "IDLE" + self.gimbal_msg = GimbalAngle() + self.gimbal_msg.yaw_mode = True + self.gimbal_msg.pitch_mode = False + # To be modified + self.gimbal_msg.yaw_angle = PyConfig.LEFT + self.gimbal_msg.pitch_angle = 0 + + def Execute(self): + try: + self.cmd_publisher.publish(self.gimbal_msg) + except: + print("Unable to Publish") + self._status = "FAILURE" + return + self._status = "SUCCESS" + + def Update(self): + return + +class GimbalRightTurn(BT.Action): + def __init__(self,name): + super(GimbalRightTurn,self).__init__(name) + self.cmd_publisher = rospy.Publisher("cmd_gimbal_angle",GimbalAngle,queue_size = 10) + self._status = "IDLE" + self.gimbal_msg = GimbalAngle() + self.gimbal_msg.yaw_mode = True + self.gimbal_msg.pitch_mode = False + # To be modified + self.gimbal_msg.yaw_angle = PyConfig.RIGHT + self.gimbal_msg.pitch_angle = 0 + + def Execute(self): + try: + self.cmd_publisher.publish(self.gimbal_msg) + except: + print("Unable to Publish") + self._status = "FAILURE" + return + self._status = "SUCCESS" + + def Update(self): + return + +class GimbalMiddleTurn(BT.Action): + def __init__(self,name): + super(GimbalMiddleTurn,self).__init__(name) + self.cmd_publisher = rospy.Publisher("cmd_gimbal_angle",GimbalAngle,queue_size = 10) + self._status = "IDLE" + self.gimbal_msg = GimbalAngle() + self.gimbal_msg.yaw_mode = True + self.gimbal_msg.pitch_mode = False + # To be modified + self.gimbal_msg.yaw_angle = PyConfig.MIDDLE + self.gimbal_msg.pitch_angle = 0 + + def Execute(self): + try: + self.cmd_publisher.publish(self.gimbal_msg) + except: + print("Unable to Publish") + self._status = "FAILURE" + return + self._status = "SUCCESS" + + def Update(self): + return self._status + +''' +REMARK: This only switch to detect but not track mode +Always return True when data published successfully +''' +class GimbalDetect(BT.Action): + def __init__(self,name): + super(GimbalDetect,self).__init__(name) + self._action_client = actionlib.SimpleActionClient('armor_detection_node_action',ArmorDetectionAction) + print("Wait For Server") + self._action_client.wait_for_server() + print("Server Connected") + self._goal = ArmorDetectionGoal() + self._goal.command = 4 + self._status = "IDLE" + + def Execute(self): + try: + self._action_client.send_goal(self._goal) + except: + rospy.logwarn("Goal failed to send") + self._status = "FAILURE" + return + self._status = "SUCCESS" + + def Update(self): + return self._status + +class GimbalTrack(BT.Action): + def __init__(self,name): + super(GimbalTrack,self).__init__(name) + self._action_client = actionlib.SimpleActionClient('armor_detection_node_action',ArmorDetectionAction) + print("Wait for Server") + self._action_client.wait_for_server() + print("Server Connected") + self._goal = ArmorDetectionGoal() + self._goal.command = 1 + self._status = "IDLE" + self.test = 0 + + def Execute(self): + try: + self._action_client.send_goal(self._goal) + except: + rospy.logwarn("Goal failed to send") + self._status = "FAILURE" + return + if self.test == 0: + self._status = "SUCCESS" + self.test = 1 + else: + self._status = "FAILURE" + self.test = 0 + + def Update(self): + return self._status + +if __name__=="__main__": + rospy.init_node("gimbal_interface_test",anonymous=True) + gimbal1 = GimbalTrack("Action1") + gimbal2 = GimbalPatrol("Action2") + gimbal01 = BT.LogicFallback("LNode1",[gimbal1,gimbal2]) + gimbal3 = GimbalTrack("Action3") + gimbal4 = GimbalPatrol("Action4") + gimbal02 = BT.LogicFallback("LNode2",[gimbal3,gimbal4]) + gimbal = BT.LogicSequential("Root",[gimbal01,gimbal02]) + rate = rospy.Rate(60) + gimbal.getName(1) + while not rospy.is_shutdown(): + gimbal.OnTick() + rate.sleep() \ No newline at end of file diff --git a/roborts_decision/scripts/shooter_task.py b/roborts_decision/scripts/shooter_task.py new file mode 100644 index 00000000..b037f761 --- /dev/null +++ b/roborts_decision/scripts/shooter_task.py @@ -0,0 +1,28 @@ +import rospy +import roslib +import tf +import time + +class ShootOnce(Action): + def __init__(self): + pass + + def Execute(self): + pass + + def Update(self): + pass + + def Cancel(): + pass + +class ShootContinuous(Action): + def __init__(self): + pass + def Execute(self,switch): + if(switch == "ON"): + pass + elif(switch=="OFF"): + pass + else: + rospy.logerr("Invalid switch at shoot action") \ No newline at end of file diff --git a/roborts_decision/scripts/test_node.py b/roborts_decision/scripts/test_node.py new file mode 100644 index 00000000..e0be49d2 --- /dev/null +++ b/roborts_decision/scripts/test_node.py @@ -0,0 +1,58 @@ +import rospy +from geometry_msgs.msg import Pose +from std_msgs.msg import String +import roslib +import tf +import numpy + +points = [[5.54,3.9],[6.73,0.82],[2.49,4.00],[1.26,1.02]] +yaws = [0, 3.14, 3.14, 0] +index = [0] +status = ["IDLE","IDLE"] # May be modified +def chassis_callback(data): + status[0] = data.data + +def switch_detect(status): + if(status[1]=="RUNNING" and status[0] != "RUNNING"): + status[1] = status[0] + print(status) + return True + else: + print "false"+str(status) + status[1] = status[0] + return False + + +def publisher(): + pub = rospy.Publisher('PyDecision/Goal', Pose, queue_size=1) + listenser = rospy.Subscriber("Actuator/Chassis",String,chassis_callback) + rospy.init_node('pose_publisher', anonymous=True) + rate = rospy.Rate(2) # Hz + while not rospy.is_shutdown(): + p = Pose() + p.position.x = points[index[0]][0] + p.position.y = points[index[0]][1] + p.position.z = 0.0 + # Make sure the quaternion is valid and normalized + q = tf.transformations.quaternion_from_euler(0,0,yaws[index[0]]) + p.orientation.x = q[0] + p.orientation.y = q[1] + p.orientation.z = q[2] + p.orientation.w = q[3] + if not(status[0]=="RUNNING"): + pub.publish(p) + if(switch_detect(status)): + if(index[0]>=3): + index[0] = 0 + else: + index[0]+= 1 + rate.sleep() + + #print("Index is: "+str(index[0])) + + +if __name__ == '__main__': + try: + publisher() + except rospy: + pass diff --git a/roborts_detection/CMakeLists.txt b/roborts_detection/CMakeLists.txt index e284d04d..e17ee618 100644 --- a/roborts_detection/CMakeLists.txt +++ b/roborts_detection/CMakeLists.txt @@ -15,6 +15,7 @@ find_package(catkin REQUIRED COMPONENTS sensor_msgs roborts_msgs roborts_common + rospy ) find_package(ProtoBuf REQUIRED) diff --git a/roborts_detection/armor_detection/CMakeLists.txt b/roborts_detection/armor_detection/CMakeLists.txt index 90c8f7b4..54f3399d 100755 --- a/roborts_detection/armor_detection/CMakeLists.txt +++ b/roborts_detection/armor_detection/CMakeLists.txt @@ -2,6 +2,8 @@ project(armor_detection) add_subdirectory(constraint_set) +add_subdirectory(lightBlob_test) + file(GLOB ProtoFiles "${CMAKE_CURRENT_SOURCE_DIR}/proto/*.proto") rrts_protobuf_generate_cpp(${CMAKE_CURRENT_SOURCE_DIR}/proto @@ -22,6 +24,7 @@ target_link_libraries(armor_detection_node PRIVATE detection::tool detection::constraint_set + detection::lightBlob_test ${PROTOBUF_LIBRARIES} ${catkin_LIBRARIES} ${OpenCV_LIBRARIES} diff --git a/roborts_detection/armor_detection/armor_detection_algorithms.h b/roborts_detection/armor_detection/armor_detection_algorithms.h index ccd1a910..ea3fbe0b 100755 --- a/roborts_detection/armor_detection/armor_detection_algorithms.h +++ b/roborts_detection/armor_detection/armor_detection_algorithms.h @@ -22,5 +22,6 @@ * Add your own algorithm harders here. */ #include "constraint_set/constraint_set.h" +#include "lightBlob_test/lightBlob_test.h" #endif // ROBORTS_DETECTION_ARMOR_DETECTION_ALGORITHMS_H \ No newline at end of file diff --git a/roborts_detection/armor_detection/armor_detection_client.cpp b/roborts_detection/armor_detection/armor_detection_client.cpp index dcddf042..89f17efd 100755 --- a/roborts_detection/armor_detection/armor_detection_client.cpp +++ b/roborts_detection/armor_detection/armor_detection_client.cpp @@ -33,18 +33,19 @@ int main(int argc, char **argv) { char command = '0'; - while (command != '4') { + while (command != '5') { std::cout << "**************************************************************************************" << std::endl; std::cout << "*********************************please send a command********************************" << std::endl; - std::cout << "1: start the action" << std::endl + std::cout << "1: detect and track" << std::endl << "2: pause the action" << std::endl << "3: stop the action" << std::endl - << "4: exit the program" << std::endl; + << "4: detect but not track"< "; std::cin >> command; if (command != '1' && command != '2' && command != '3' && command != '4') { - std::cout << "please inpugain!" << std::endl; + std::cout << "please input again!" << std::endl; std::cout << "> "; std::cin >> command; } @@ -67,6 +68,11 @@ int main(int argc, char **argv) { ROS_INFO("I am cancelling the request"); ac.cancelGoal(); break; + case '4': + goal.command = 4; + ROS_INFO("Detect not track"); + ac.sendGoal(goal); + break; default: break; } diff --git a/roborts_detection/armor_detection/armor_detection_node.cpp b/roborts_detection/armor_detection/armor_detection_node.cpp index c6d11695..2cf28b0f 100755 --- a/roborts_detection/armor_detection/armor_detection_node.cpp +++ b/roborts_detection/armor_detection/armor_detection_node.cpp @@ -18,6 +18,7 @@ #include #include "armor_detection_node.h" + namespace roborts_detection { ArmorDetectionNode::ArmorDetectionNode(): @@ -41,7 +42,10 @@ ArmorDetectionNode::ArmorDetectionNode(): ErrorInfo ArmorDetectionNode::Init() { enemy_info_pub_ = enemy_nh_.advertise("cmd_gimbal_angle", 100); + enemy_flag_pub_ = enemy_nh_.advertise("Detection/flag", 100); ArmorDetectionAlgorithms armor_detection_param; + yes<<"DETECTED"; + no<<"NOT_DETECTED"; std::string file_name = ros::package::getPath("roborts_detection") + "/armor_detection/config/armor_detection.prototxt"; bool read_state = roborts_common::ReadProtoFromTextFile(file_name, &armor_detection_param); @@ -89,6 +93,7 @@ void ArmorDetectionNode::ActionCB(const roborts_msgs::ArmorDetectionGoal::ConstP switch (data->command) { case 1: + enable_track = true; StartThread(); break; case 2: @@ -97,19 +102,23 @@ void ArmorDetectionNode::ActionCB(const roborts_msgs::ArmorDetectionGoal::ConstP case 3: StopThread(); break; + case 4: + enable_track = false; + StartThread(); + break; default: break; } ros::Rate rate(25); while(ros::ok()) { - + // Check whether Preempted every time if(as_.isPreemptRequested()) { as_.setPreempted(); return; } { - std::lock_guard guard(mutex_); + std::lock_guard guard(mutex_); // Since detection thread will write xyz, this mutex can prevent problems if (undetected_count_ != 0) { feedback.detected = true; feedback.error_code = error_info_.error_code(); @@ -150,8 +159,8 @@ void ArmorDetectionNode::ExecuteLoop() { while(running_) { usleep(1); if (node_state_ == NodeState::RUNNING) { - cv::Point3f target_3d; - ErrorInfo error_info = armor_detector_->DetectArmor(detected_enemy_, target_3d); + cv::Point3f target_3d;//hat ever it runs out put will be + ErrorInfo error_info = armor_detector_->DetectArmor(detected_enemy_, target_3d); // Whatever algo is the result will be enemy pos as well as flag { std::lock_guard guard(mutex_); x_ = target_3d.x; @@ -190,14 +199,26 @@ void ArmorDetectionNode::ExecuteLoop() { } void ArmorDetectionNode::PublishMsgs() { - enemy_info_pub_.publish(gimbal_angle_); + if (enable_track) + enemy_info_pub_.publish(gimbal_angle_); + if (detected_enemy_) + { + detectionFlag.data = yes.str(); + enemy_flag_pub_.publish(detectionFlag); + } + else + { + detectionFlag.data = no.str(); + enemy_flag_pub_.publish(detectionFlag); + } + } void ArmorDetectionNode::StartThread() { ROS_INFO("Armor detection node started!"); running_ = true; armor_detector_->SetThreadState(true); - if(node_state_ == NodeState::IDLE) { + if(node_state_ == NodeState::IDLE) { // Prevent re-run armor_detection_thread_ = std::thread(&ArmorDetectionNode::ExecuteLoop, this); } node_state_ = NodeState::RUNNING; diff --git a/roborts_detection/armor_detection/armor_detection_node.h b/roborts_detection/armor_detection/armor_detection_node.h index c533f7c4..4d595bc1 100755 --- a/roborts_detection/armor_detection/armor_detection_node.h +++ b/roborts_detection/armor_detection/armor_detection_node.h @@ -22,11 +22,14 @@ #include #include #include +#include +#include #include #include "actionlib/server/simple_action_server.h" -#include "roborts_msgs/GimbalAngle.h" -#include "roborts_msgs/GimbalRate.h" +#include "roborts_msgs/GimbalAngle.h" // Useful info +#include "roborts_msgs/GimbalRate.h" // Abandoned +#include "std_msgs/String.h" #include "roborts_msgs/ArmorDetectionAction.h" #include "alg_factory/algorithm_factory.h" @@ -40,6 +43,8 @@ #include "armor_detection_algorithms.h" #include "gimbal_control.h" + + namespace roborts_detection { using roborts_common::NodeState; @@ -107,12 +112,16 @@ class ArmorDetectionNode { ros::NodeHandle nh_; ros::NodeHandle enemy_nh_; ros::Publisher enemy_info_pub_; + ros::Publisher enemy_flag_pub_; std::shared_ptr cv_toolbox_; actionlib::SimpleActionServer as_; roborts_msgs::GimbalAngle gimbal_angle_; - + std_msgs::String detectionFlag; + std::stringstream yes; + std::stringstream no; //! control model GimbalContrl gimbal_control_; + bool enable_track = false; }; } //namespace roborts_detection diff --git a/roborts_detection/armor_detection/config/armor_detection.prototxt b/roborts_detection/armor_detection/config/armor_detection.prototxt index ce4fe124..df0a45ec 100755 --- a/roborts_detection/armor_detection/config/armor_detection.prototxt +++ b/roborts_detection/armor_detection/config/armor_detection.prototxt @@ -4,10 +4,10 @@ undetected_armor_delay: 10 camera_name: "back_camera" camera_gimbal_transform { offset_x :0 - offset_y :10 + offset_y :15 offset_z :9 - offset_pitch :-2.5 - offset_yaw : 4.5 + offset_pitch :0 + offset_yaw : 0 } projectile_model_info { diff --git a/roborts_detection/armor_detection/constraint_set/constraint_set.cpp b/roborts_detection/armor_detection/constraint_set/constraint_set.cpp index 927dc4e4..e423a2a9 100755 --- a/roborts_detection/armor_detection/constraint_set/constraint_set.cpp +++ b/roborts_detection/armor_detection/constraint_set/constraint_set.cpp @@ -153,7 +153,7 @@ ErrorInfo ConstraintSet::DetectArmor(bool &detected, cv::Point3f &target_3d) { } else detected = false; if(enable_debug_) { - cv::imshow("relust_img_", src_img_); + cv::imshow("result_img_", src_img_); } lights.clear(); @@ -211,7 +211,7 @@ void ConstraintSet::DetectLights(const cv::Mat &src, std::vectorDrawRotatedRect(show_lights_before_filter_, single_light, cv::Scalar(0, 255, 0), 2, light_info.angle_); - single_light.angle = light_info.angle_; + single_light.angle = light_info.angle_; // In degree lights.push_back(single_light); break; } @@ -445,7 +445,7 @@ void ConstraintSet::CalcArmorInfo(std::vector &armor_points, armor_points.push_back(lift_rd); } - +// Template for solve PnP void ConstraintSet::SolveArmorCoordinate(const float width, const float height) { armor_points_.emplace_back(cv::Point3f(-width/2, height/2, 0.0)); diff --git a/roborts_detection/armor_detection/demo.prototxt b/roborts_detection/armor_detection/demo.prototxt new file mode 100644 index 00000000..23d763ea --- /dev/null +++ b/roborts_detection/armor_detection/demo.prototxt @@ -0,0 +1,5 @@ +thresholds { + item1: 100 + item2: 99 + item3: 190 +} diff --git a/roborts_detection/armor_detection/gimbal_control.cpp b/roborts_detection/armor_detection/gimbal_control.cpp index 3ab86b27..cfa6455d 100644 --- a/roborts_detection/armor_detection/gimbal_control.cpp +++ b/roborts_detection/armor_detection/gimbal_control.cpp @@ -61,9 +61,9 @@ float GimbalContrl::GetPitch(float x, float y, float v) { } void GimbalContrl::Transform(cv::Point3f &postion, float &pitch, float &yaw) { - pitch = - -GetPitch((postion.z + offset_.z) / 100, -(postion.y + offset_.y) / 100, 15) + (float)(offset_pitch_ * 3.1415926535 / 180); + //pitch =-GetPitch((postion.z + offset_.z) / 100, -(postion.y + offset_.y) / 100, 15) + (float)(offset_pitch_ * 3.1415926535 / 180); //yaw positive direction :anticlockwise + pitch = (float) (atan2(postion.y + offset_.y, postion.z + offset_.z)) + (float)(offset_pitch_ * 3.1415926535 / 180); yaw = -(float) (atan2(postion.x + offset_.x, postion.z + offset_.z)) + (float)(offset_yaw_ * 3.1415926535 / 180); } diff --git a/roborts_detection/armor_detection/lightBlob_test/CMakeLists.txt b/roborts_detection/armor_detection/lightBlob_test/CMakeLists.txt new file mode 100644 index 00000000..8d75b78e --- /dev/null +++ b/roborts_detection/armor_detection/lightBlob_test/CMakeLists.txt @@ -0,0 +1,20 @@ +project(lightBlob_test) + +add_library(lightBlob_test + SHARED + lightBlob_test.cpp + ) + +add_library(detection::lightBlob_test ALIAS lightBlob_test) + +target_link_libraries(${PROJECT_NAME} + PUBLIC + detection::tool + ${catkin_LIBRARIES} + ${OpenCV_LIBRARIES} + ) + +target_include_directories(${PROJECT_NAME} + PUBLIC + ${catkin_INCLUDE_DIRS} + ) \ No newline at end of file diff --git a/roborts_detection/armor_detection/lightBlob_test/lightBlob_test.cpp b/roborts_detection/armor_detection/lightBlob_test/lightBlob_test.cpp new file mode 100644 index 00000000..e702f795 --- /dev/null +++ b/roborts_detection/armor_detection/lightBlob_test/lightBlob_test.cpp @@ -0,0 +1,208 @@ +#include "lightBlob_test.h" +#include "timer/timer.h" +#include "io/io.h" +#include +#include + +namespace roborts_detection +{ + bool compare(LBInfo &l1, LBInfo &l2) + { + return l1.radius > l2.radius; + } + + LightBlob::LightBlob(std::shared_ptr cv_toolbox): + ArmorDetectionBase(cv_toolbox){ + filter_x_count_ = 0; + filter_y_count_ = 0; + filter_distance_count_ = 0; + filter_pitch_count_ = 0; + filter_yaw_count_ = 0; + read_index_ = -1; + detection_time_ = 0; + thread_running_ = false; + enable_debug_ = true; // Tobo Modified + enemy_color_ = 1; // Means blue + int get_intr_state = -1; + int get_dist_state = -1; + LoadParam(); + while((get_dist_state<0) || (get_intr_state<0)) + { + ROS_WARN("wait for camera driver launch %d", get_intr_state); + usleep(50000); + ros::spinOnce(); + get_intr_state = cv_toolbox_->GetCameraMatrix(intrinsic_matrix_); + get_dist_state = cv_toolbox_->GetCameraMatrix(distortion_coeffs_); + + } + error_info_ = ErrorInfo(roborts_common::OK); + } + + ErrorInfo LightBlob::DetectArmor(bool &detected, cv::Point3f &target_3d) + { + auto img_begin = std::chrono::high_resolution_clock::now(); + bool sleep_by_diff_flag = true; + // Below is a time match which make sure real time performance as well as + // Breakable thread + while(true) + { + if(!thread_running_) + { + ErrorInfo error_info(ErrorCode::STOP_DETECTION); + return error_info; + } + read_index_ = cv_toolbox_->NextImage(src_img_); + if(read_index_ < 0) + { + if(detection_time_ == 0) + { + usleep(20000); + continue; + } + else + { + double capture_time = 0; + cv_toolbox_->GetCaptureTime(capture_time); + if(capture_time == 0) // The very beginning + { + usleep(20000); + continue; + } + else if(capture_time > detection_time_ && sleep_by_diff_flag) + { + usleep((unsigned int)(capture_time - detection_time_)); + sleep_by_diff_flag = false; + continue; + } + else + { + usleep(500); + continue; + } + } + } + else + { + break; + } + + } + + auto detection_begin = std::chrono::high_resolution_clock::now(); + if(enable_debug_) + { + show_minus = src_img_.clone(); + show_thresh= src_img_.clone(); + show_raw = src_img_.clone(); + } + show_minus = cv_toolbox_->DistillationColor(src_img_,enemy_color_,false); + if(enable_debug_) + cv::imshow("minus",show_minus); + cv::threshold(show_minus,show_thresh,80,255,cv::THRESH_BINARY); + if(enable_debug_) + cv::imshow("thresh",show_thresh); + std::vector> cnts; + cnts = cv_toolbox_->FindContours(show_thresh); + // Using list of lb_info to represent light blob positional data + std::list candidates; + LBInfo target; + // Constrain operation filtered proper armor box + if(cnts.size() > 0) + { + for(int i=0;i cnt = cnts[i]; + double lb_area = cv::contourArea(cnt); + if (lb_area >=500 && lb_area <= 30000 ) + { + LBInfo lb; + cv::minEnclosingCircle(cnt,lb.center,lb.radius); + if(lb.radius*lb.radius*3.141592 <= 1.2*lb_area) + { + for(int j=0;j 0) + { + candidates.sort(compare); + detected = true; + target = *candidates.begin(); + + double df = ENEMY_SIZE/tan(MAX_ANGLE); + double yaw = atan( (target.center.x-cv_toolbox_->GetCameraWidth()/2) *tan(MAX_ANGLE)/(cv_toolbox_->GetCameraHeight()/2)); + // Need to be determined + double pitch = -atan( (target.center.y-cv_toolbox_->GetCameraHeight()/2) *tan(MAX_ANGLE)/(cv_toolbox_->GetCameraHeight()/2)); + target_3d.z = (cv_toolbox_->GetCameraHeight()/2*df)/target.radius; + target_3d.x = target_3d.z * tan(yaw); + target_3d.y = target_3d.z * tan(pitch); + if(enable_debug_) + { + cv::Point p(int(target.center.x),int(target.center.y)); + cv::circle(show_raw,p,target.radius,cv::Scalar(0,255,0)); + //std::stringstream ss; + //ss<<"The Distance is"; + //ss<ReadComplete(read_index_); + ROS_INFO("read complete"); + detection_time_ = std::chrono::duration> + (std::chrono::high_resolution_clock::now() - detection_begin).count(); + return error_info_; + } + + void LightBlob::SignalFilter(double &new_num, double &old_num, unsigned int &filter_count, double max_diff) + { + if(fabs(new_num - old_num) > max_diff && filter_count < 2) + { + filter_count++; + new_num+= max_diff; + } + else + { + filter_count = 0; + old_num = new_num; + } + } + + void LightBlob::LoadParam() + { + return; + } + + void LightBlob::SetThreadState(bool thread_state) + { + thread_running_ = thread_state; + } + + LightBlob::~LightBlob() + { + // Temperorily do nothing. + } + +} \ No newline at end of file diff --git a/roborts_detection/armor_detection/lightBlob_test/lightBlob_test.h b/roborts_detection/armor_detection/lightBlob_test/lightBlob_test.h new file mode 100644 index 00000000..260d8060 --- /dev/null +++ b/roborts_detection/armor_detection/lightBlob_test/lightBlob_test.h @@ -0,0 +1,75 @@ +#ifndef ROBORTS_DETECTION_ARMOR_LIGHT_BLOB_ +#define ROBORTS_DETECTION_ARMOR_LIGHT_BLOB_ + +#include +#include +#include +#include + +#include +#include +#include "state/error_code.h" + +#include "cv_toolbox.h" +#include "../armor_detection_base.h" + +#define ENEMY_SIZE 7.45 // Plate radius size in cm +#define MAX_ANGLE 0.3191713446 //Max Vertical viewing angle in Radius + +namespace roborts_detection +{ + using roborts_common::ErrorCode; + using roborts_common::ErrorInfo; + + // Over load the operator for LBInfo compare + + class LBInfo + { + public: + cv::Point2f center; + float radius; + }; + + class LightBlob: public ArmorDetectionBase + { + public: + LightBlob(std::shared_ptr cv_toolbox); + void LoadParam() override; + ErrorInfo DetectArmor(bool &detected,cv::Point3f &target_3d) override; + void CalcControlInfo(const LBInfo & lightblob,cv::Point3f &target_3d); + void SignalFilter(double &new_num, double &old_num,unsigned int &filter_count, double max_diff); + void SetThreadState(bool thread_state) override; + ~LightBlob() final; + private: + ErrorInfo error_info_; + unsigned int filter_x_count_; + unsigned int filter_y_count_; + unsigned int filter_z_count_; + unsigned int filter_distance_count_; + unsigned int filter_pitch_count_; + unsigned int filter_yaw_count_; + + cv::Mat src_img_; + cv::Mat intrinsic_matrix_; + cv::Mat distortion_coeffs_; + int read_index_; + double detection_time_; + + bool enable_debug_; + unsigned int enemy_color_; + + cv::Mat show_raw; + cv::Mat show_minus; + cv::Mat show_thresh; + cv::Mat show_result; + + ros::NodeHandle nh; + bool thread_running_; + + }; + roborts_common::REGISTER_ALGORITHM(ArmorDetectionBase,"light_blob_test",LightBlob,std::shared_ptr); + +} + +#endif + diff --git a/roborts_detection/armor_detection/t.txt b/roborts_detection/armor_detection/t.txt new file mode 100644 index 00000000..31e0fce5 --- /dev/null +++ b/roborts_detection/armor_detection/t.txt @@ -0,0 +1 @@ +helloworld diff --git a/roborts_detection/armor_detection/test.txt b/roborts_detection/armor_detection/test.txt new file mode 100644 index 00000000..208949cd --- /dev/null +++ b/roborts_detection/armor_detection/test.txt @@ -0,0 +1,3 @@ +Helloworld +This is new +123456789 diff --git a/roborts_detection/lightBlob_test/lightBlob_test.cpp b/roborts_detection/lightBlob_test/lightBlob_test.cpp new file mode 100644 index 00000000..68da2283 --- /dev/null +++ b/roborts_detection/lightBlob_test/lightBlob_test.cpp @@ -0,0 +1,168 @@ +#include "light_blob.h" +#include "timer/timer.h" +#include "io/io.h" + +namespace roborts_detection +{ + LightBlob::LightBlob(std::shared_ptr cv_toolbox): + ArmorDetectionBase(cv_toolbox){ + filter_x_count_ = 0; + filter_y_count_ = 0; + filter_distance_count_ = 0; + filter_pitch_count_ = 0; + filter_yaw_count_ = 0; + read_index_ = -1; + detection_time_ = 0; + thread_running_ = false; + enable_debug_ = true; // Tobo Modified + enemy_color_ = 1; // Means blue + int get_intr_state = -1; + int get_dist_state = -1; + LoadParam(); + while((get_dist_state<0) || (get_intr_state<0)) + { + ROS_WARN("wait for camera driver launch %d", get_intr_state); + usleep(50000); + ros::spinOnce(); + get_intr_state = cv_toolbox_->GetCameraMatrix(intrinsic_matrix_); + get_dist_state = cv_toolbox_->GetCameraMatrix(distortion_coeffs_); + + } + error_info_ = ErrorInfo(roborts_common::OK); + } + + ErrorInfo LightBlob::DetectArmor(bool &detected, cv::Point3f &target_3d) + { + auto img_begin = std::chrono::high_resolution_clock::now(); + bool sleep_by_diff_flag = true; + // Below is a time match which make sure real time performance as well as + // Breakable thread + while(true) + { + if(!thread_running_) + { + ErrorInfo error_info(ErrorCode::STOP_DETECTION); + return error_info; + } + read_index_ = cv_toolbox_->NextImage(src_img_); + if(read_index_ < 0) + { + if(detection_time_ == 0) + { + usleep(20000); + continue; + } + else + { + double capture_time = 0; + cv_toolbox_->GetCaptureTime(capture_time); + if(capture_time == 0) // The very beginning + { + usleep(20000); + continue; + } + else if(capture_time > detection_time_ && sleep_by_diff_flag) + { + usleep((unsigned int)(capture_time - detection_time)); + sleep_by_diff_flag = false; + continue; + } + else + { + usleep(500); + continue; + } + } + else + { + break; + } + + } + } + + auto detection_begin = std::chrono::high_resolution_clock::now(); + + show_minus = cv_toolbox_.DistillationColor(src_img_,enemy_color_,false); + if(enable_debug_) + cv::imshow("minus",show_minus); + cv::threshold(src_img_,show_thresh,80,255,cv::THRESH_BINARY); + if(enable_debug_) + cv::imshow("thresh",show_thresh); + std::vector> cnts; + cv::cvtColor() + cnts = cv_toolbox_.FindContours(show_thresh); + // Using list of lb_info to represent light blob positional data + std::list candidates; + // Constrain operation filtered proper armor box + if(cnts.size() > 0) + { + for(int i=0;i cnt = cnts[i] + double lb_area = cv::contourArea(cnt); + if (lb_area <=10 ||lb_area >= 1000 ) continue; + LBInfo lb; + cv::minEnclosingCircle(cnt,lb.center,lb.radius); + if(lb.radius*lb.radius*3.141592 > 1.2*lb_area) continue; + for(int j=0;j 0) + { + std::sort(candidiates.begin(),candidates.end()); + } + + LBInfo target = candidates[0]; + detected = true; + double df = ENEMY_SIZE/tan(MAX_ANGLE); + double yaw = atan( (target.center.x-cv_toolbox_.GetCameraWidth()/2) *tan(MAX_ANGLE)/(cv_toolbox_.GetCameraHeight()/2)); + // Need to be determined + double pitch = -atan( (target.center.y-cv_toolbox_.GetCameraHeight()/2) *tan(MAX_ANGLE)/(cv_toolbox_.GetCameraHeight()/2)); + target_3d.z = (cv_toolbox_.GetCameraHeight()/2*df)/target.radius; + target_3d.x = target_3d.z * tan(yaw); + target_3d.y = target_3d.z * tan(pitch); + + auto c == cv::waitKey(1); + if(c=="q") + { + cv::destroyAllWindows(); + } + } + } + + void LightBlob::SignalFilter(double &new_num, double &old_num, unsigned int &filter_count, double max_diff) + { + if(fabs(new_num - old_num) > max_diff && filter_count < 2) + { + filter_count++; + new_num+= max_diff; + } + else + { + filter_count = 0; + old_num = new_num; + } + } + + void LightBlob::LoadParam() + { + return; + } + + void LightBlob::SetThreadState(bool thread_state) + { + thread_running_ = thread_state; + } + + LightBlob::~LightBlob() + { + // Temperorily do nothing. + } + +} \ No newline at end of file diff --git a/roborts_detection/util/cv_toolbox.h b/roborts_detection/util/cv_toolbox.h index 40afe355..530375c6 100644 --- a/roborts_detection/util/cv_toolbox.h +++ b/roborts_detection/util/cv_toolbox.h @@ -115,6 +115,7 @@ class CVToolbox { } void ImageCallback(const sensor_msgs::ImageConstPtr &img_msg, const sensor_msgs::CameraInfoConstPtr &camera_info_msg) { + //ROS_INFO("Callback Invoked!"); if(!get_img_info_){ camera_info_ = *camera_info_msg; capture_begin_ = std::chrono::high_resolution_clock::now(); @@ -153,7 +154,7 @@ class CVToolbox { if (buffer_state_[latest_index_] == BufferState::WRITE) { buffer_state_[latest_index_] = BufferState::READ; } else { - ROS_INFO("No image is available"); + //ROS_INFO("No image is available"); lock_.unlock(); return temp_index; } @@ -226,12 +227,16 @@ class CVToolbox { std::vector bgr; cv::split(src_img, bgr); if (color == 1) { - cv::Mat result_img; - cv::subtract(bgr[2], bgr[1], result_img); + cv::Mat buffer_img1,buffer_img2,result_img; + cv::subtract(bgr[2], bgr[1], buffer_img1); + cv::subtract(bgr[2], bgr[0], buffer_img2); + cv::add(buffer_img1,buffer_img2,result_img); return result_img; } else if (color == 0) { - cv::Mat result_img; - cv::subtract(bgr[0], bgr[2], result_img); + cv::Mat buffer_img1,buffer_img2,result_img; + cv::subtract(bgr[0], bgr[1], buffer_img1); + cv::subtract(bgr[0], bgr[2], buffer_img2); + cv::add(buffer_img1,buffer_img2,result_img); return result_img; } } diff --git a/roborts_localization/config/localization.yaml b/roborts_localization/config/localization.yaml index 29bf05e2..3f46ebae 100644 --- a/roborts_localization/config/localization.yaml +++ b/roborts_localization/config/localization.yaml @@ -8,8 +8,8 @@ transform_tolerance : 0.1 #8.40 #1.0 #14.35 #1.0 initial_pose_x : 1 -initial_pose_y : 1 -initial_pose_a : 3.14 +initial_pose_y : 1 +initial_pose_a : 0 initial_cov_xx : 0.1 initial_cov_yy : 0.1 initial_cov_aa : 0.1 diff --git a/roborts_localization/localization_node.cpp b/roborts_localization/localization_node.cpp index 06cba6f1..4c1481e6 100644 --- a/roborts_localization/localization_node.cpp +++ b/roborts_localization/localization_node.cpp @@ -191,6 +191,8 @@ void LocalizationNode::LaserScanCallback(const sensor_msgs::LaserScan::ConstPtr } } +// TODO: Implement UWB update logic + void LocalizationNode::PublishVisualize(){ @@ -235,7 +237,7 @@ bool LocalizationNode::PublishTf() { LOG_ERROR << "Failed to subtract base to odom transform" << e.what(); return false; } - + // General transform applicable to all kinds of datas latest_tf_ = tf::Transform(tf::Quaternion(odom_to_map.getRotation()), tf::Point(odom_to_map.getOrigin())); latest_tf_valid_ = true; diff --git a/roborts_localization/localization_node.h b/roborts_localization/localization_node.h index ac961656..ebf3682d 100644 --- a/roborts_localization/localization_node.h +++ b/roborts_localization/localization_node.h @@ -16,7 +16,7 @@ ***************************************************************************/ #ifndef ROBORTS_LOCALIZATION_LOCALIZATION_NODE_H -#define ROBORTS_LOCALIZATION_LOCALIZATION_NODE_H +#define ROBORTS_LOCALIZATION_LOCALIZATION_NODE_Hen #include #include @@ -71,6 +71,12 @@ class LocalizationNode { */ void InitialPoseCallback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &init_pose_msg); +/** + * @brief Uwb Data Callback function as in main loop + * @param uwb_msg + */ +//void UwbCallback(const geometry_msgs::PoseStamped::ConstPtr $uwb_msg); + /** * @brief Publish visualize messages */ @@ -113,7 +119,7 @@ class LocalizationNode { //ROS Subscriber ros::Subscriber initial_pose_sub_; ros::Subscriber map_sub_; - ros::Subscriber uwb_pose_sub_; + ros::Subscriber uwb_pose_sub_; // To be initialized ros::Subscriber ground_truth_sub_; std::shared_ptr> laser_scan_sub_; std::unique_ptr> laser_scan_filter_; @@ -135,7 +141,7 @@ class LocalizationNode { std::string laser_topic_; Vec3d init_pose_; Vec3d init_cov_; -// bool enable_uwb_; + bool enable_uwb_; ros::Duration transform_tolerance_; bool publish_visualize_; @@ -152,6 +158,7 @@ class LocalizationNode { HypPose hyp_pose_; geometry_msgs::PoseArray particlecloud_msg_; geometry_msgs::PoseStamped pose_msg_; + geometry_msgs::PoseStamped uwb_pose_; ros::Time last_laser_msg_timestamp_; tf::Transform latest_tf_; tf::Stamped latest_odom_pose_; diff --git a/roborts_msgs/action/ArmorDetection.action b/roborts_msgs/action/ArmorDetection.action index 05b32d5b..59c69379 100755 --- a/roborts_msgs/action/ArmorDetection.action +++ b/roborts_msgs/action/ArmorDetection.action @@ -2,6 +2,7 @@ #command == 1 start #command == 2 pause #command == 3 stop +#command == 4 Detect Only int32 command --- float32 result diff --git a/roborts_planning/global_planner/CMakeLists.txt b/roborts_planning/global_planner/CMakeLists.txt index e194c7c7..8bbf8140 100755 --- a/roborts_planning/global_planner/CMakeLists.txt +++ b/roborts_planning/global_planner/CMakeLists.txt @@ -1,6 +1,6 @@ project(global_planner) -add_subdirectory(a_star_planner) +add_subdirectory(spfa_planner) set(CMAKE_BUILD_TYPE Release) file(GLOB ProtoFiles "${CMAKE_CURRENT_SOURCE_DIR}/proto/*.proto") rrts_protobuf_generate_cpp(${CMAKE_CURRENT_SOURCE_DIR}/proto GlobalPlannerProtoSrc GlobalPlannerProtoHds ${ProtoFiles}) @@ -14,7 +14,7 @@ add_executable(${PROJECT_NAME}_node ) target_link_libraries(${PROJECT_NAME}_node PRIVATE - planning::global_planner::a_star_planner + planning::global_planner::spfa_planner roborts_costmap ${catkin_LIBRARIES} ${Boost_LIBRARIES} diff --git a/roborts_planning/global_planner/a_star_planner/a_star_planner.cpp b/roborts_planning/global_planner/a_star_planner/a_star_planner.cpp index 4f29deb3..3d0a0bd9 100755 --- a/roborts_planning/global_planner/a_star_planner/a_star_planner.cpp +++ b/roborts_planning/global_planner/a_star_planner/a_star_planner.cpp @@ -19,262 +19,262 @@ namespace roborts_global_planner{ -using roborts_common::ErrorCode; -using roborts_common::ErrorInfo; + using roborts_common::ErrorCode; + using roborts_common::ErrorInfo; -AStarPlanner::AStarPlanner(CostmapPtr costmap_ptr) : - GlobalPlannerBase::GlobalPlannerBase(costmap_ptr), - gridmap_width_(costmap_ptr_->GetCostMap()->GetSizeXCell()), - gridmap_height_(costmap_ptr_->GetCostMap()->GetSizeYCell()), - cost_(costmap_ptr_->GetCostMap()->GetCharMap()) { + AStarPlanner::AStarPlanner(CostmapPtr costmap_ptr) : + GlobalPlannerBase::GlobalPlannerBase(costmap_ptr), + gridmap_width_(costmap_ptr_->GetCostMap()->GetSizeXCell()), + gridmap_height_(costmap_ptr_->GetCostMap()->GetSizeYCell()), + cost_(costmap_ptr_->GetCostMap()->GetCharMap()) { - AStarPlannerConfig a_star_planner_config; - std::string full_path = ros::package::getPath("roborts_planning") + "/global_planner/a_star_planner/"\ + AStarPlannerConfig a_star_planner_config; + std::string full_path = ros::package::getPath("roborts_planning") + "/global_planner/a_star_planner/"\ "config/a_star_planner_config.prototxt"; - if (!roborts_common::ReadProtoFromTextFile(full_path.c_str(), - &a_star_planner_config)) { - ROS_ERROR("Cannot load a star planner protobuf configuration file."); - } - // AStarPlanner param config - heuristic_factor_ = a_star_planner_config.heuristic_factor(); - inaccessible_cost_ = a_star_planner_config.inaccessible_cost(); - goal_search_tolerance_ = a_star_planner_config.goal_search_tolerance()/costmap_ptr->GetCostMap()->GetResolution(); -} - -AStarPlanner::~AStarPlanner(){ - cost_ = nullptr; -} - -ErrorInfo AStarPlanner::Plan(const geometry_msgs::PoseStamped &start, - const geometry_msgs::PoseStamped &goal, - std::vector &path) { - - unsigned int start_x, start_y, goal_x, goal_y, tmp_goal_x, tmp_goal_y; - unsigned int valid_goal[2]; - unsigned int shortest_dist = std::numeric_limits::max(); - bool goal_valid = false; - - if (!costmap_ptr_->GetCostMap()->World2Map(start.pose.position.x, - start.pose.position.y, - start_x, - start_y)) { - ROS_WARN("Failed to transform start pose from map frame to costmap frame"); - return ErrorInfo(ErrorCode::GP_POSE_TRANSFORM_ERROR, - "Start pose can't be transformed to costmap frame."); - } - if (!costmap_ptr_->GetCostMap()->World2Map(goal.pose.position.x, - goal.pose.position.y, - goal_x, - goal_y)) { - ROS_WARN("Failed to transform goal pose from map frame to costmap frame"); - return ErrorInfo(ErrorCode::GP_POSE_TRANSFORM_ERROR, - "Goal pose can't be transformed to costmap frame."); - } - if (costmap_ptr_->GetCostMap()->GetCost(goal_x,goal_y)GetCostMap()->GetCost(tmp_goal_x, tmp_goal_y); - unsigned int dist = abs(goal_x - tmp_goal_x) + abs(goal_y - tmp_goal_y); - if (cost < inaccessible_cost_ && dist < shortest_dist ) { - shortest_dist = dist; - valid_goal[0] = tmp_goal_x; - valid_goal[1] = tmp_goal_y; - goal_valid = true; + if (!roborts_common::ReadProtoFromTextFile(full_path.c_str(), + &a_star_planner_config)) { + ROS_ERROR("Cannot load a star planner protobuf configuration file."); } - tmp_goal_x += 1; - } - tmp_goal_y += 1; - } - } - ErrorInfo error_info; - if (!goal_valid){ - error_info=ErrorInfo(ErrorCode::GP_GOAL_INVALID_ERROR); - path.clear(); - } - else{ - unsigned int start_index, goal_index; - start_index = costmap_ptr_->GetCostMap()->GetIndex(start_x, start_y); - goal_index = costmap_ptr_->GetCostMap()->GetIndex(valid_goal[0], valid_goal[1]); - - costmap_ptr_->GetCostMap()->SetCost(start_x, start_y,roborts_costmap::FREE_SPACE); - - if(start_index == goal_index){ - error_info=ErrorInfo::OK(); - path.clear(); - path.push_back(start); - path.push_back(goal); - } - else{ - error_info = SearchPath(start_index, goal_index, path); - if ( error_info.IsOK() ){ - path.back().pose.orientation = goal.pose.orientation; - path.back().pose.position.z = goal.pose.position.z; - } + // AStarPlanner param config + heuristic_factor_ = a_star_planner_config.heuristic_factor(); + inaccessible_cost_ = a_star_planner_config.inaccessible_cost(); + goal_search_tolerance_ = a_star_planner_config.goal_search_tolerance()/costmap_ptr->GetCostMap()->GetResolution(); } - } - + AStarPlanner::~AStarPlanner(){ + cost_ = nullptr; + } - return error_info; -} + ErrorInfo AStarPlanner::Plan(const geometry_msgs::PoseStamped &start, + const geometry_msgs::PoseStamped &goal, + std::vector &path) { + + unsigned int start_x, start_y, goal_x, goal_y, tmp_goal_x, tmp_goal_y; + unsigned int valid_goal[2]; + unsigned int shortest_dist = std::numeric_limits::max(); + bool goal_valid = false; + + if (!costmap_ptr_->GetCostMap()->World2Map(start.pose.position.x, + start.pose.position.y, + start_x, + start_y)) { + ROS_WARN("Failed to transform start pose from map frame to costmap frame"); + return ErrorInfo(ErrorCode::GP_POSE_TRANSFORM_ERROR, + "Start pose can't be transformed to costmap frame."); + } + if (!costmap_ptr_->GetCostMap()->World2Map(goal.pose.position.x, + goal.pose.position.y, + goal_x, + goal_y)) { + ROS_WARN("Failed to transform goal pose from map frame to costmap frame"); + return ErrorInfo(ErrorCode::GP_POSE_TRANSFORM_ERROR, + "Goal pose can't be transformed to costmap frame."); + } + if (costmap_ptr_->GetCostMap()->GetCost(goal_x,goal_y)GetCostMap()->GetCost(tmp_goal_x, tmp_goal_y); + unsigned int dist = abs(static_cast(goal_x - tmp_goal_x)) + abs(static_cast(goal_y - tmp_goal_y)); + if (cost < inaccessible_cost_ && dist < shortest_dist ) { + shortest_dist = dist; + valid_goal[0] = tmp_goal_x; + valid_goal[1] = tmp_goal_y; + goal_valid = true; + } + tmp_goal_x += 1; + } + tmp_goal_y += 1; + } + } + ErrorInfo error_info; + if (!goal_valid){ + error_info=ErrorInfo(ErrorCode::GP_GOAL_INVALID_ERROR); + path.clear(); + } + else{ + unsigned int start_index, goal_index; + start_index = costmap_ptr_->GetCostMap()->GetIndex(start_x, start_y); + goal_index = costmap_ptr_->GetCostMap()->GetIndex(valid_goal[0], valid_goal[1]); + + costmap_ptr_->GetCostMap()->SetCost(start_x, start_y,roborts_costmap::FREE_SPACE); + + if(start_index == goal_index){ + error_info=ErrorInfo::OK(); + path.clear(); + path.push_back(start); + path.push_back(goal); + } + else{ + error_info = SearchPath(start_index, goal_index, path); + if ( error_info.IsOK() ){ + path.back().pose.orientation = goal.pose.orientation; + path.back().pose.position.z = goal.pose.position.z; + } + } -ErrorInfo AStarPlanner::SearchPath(const int &start_index, - const int &goal_index, - std::vector &path) { + } - g_score_.clear(); - f_score_.clear(); - parent_.clear(); - state_.clear(); - gridmap_width_ = costmap_ptr_->GetCostMap()->GetSizeXCell(); - gridmap_height_ = costmap_ptr_->GetCostMap()->GetSizeYCell(); - ROS_INFO("Search in a map %d", gridmap_width_*gridmap_height_); - cost_ = costmap_ptr_->GetCostMap()->GetCharMap(); - g_score_.resize(gridmap_height_ * gridmap_width_, std::numeric_limits::max()); - f_score_.resize(gridmap_height_ * gridmap_width_, std::numeric_limits::max()); - parent_.resize(gridmap_height_ * gridmap_width_, std::numeric_limits::max()); - state_.resize(gridmap_height_ * gridmap_width_, SearchState::NOT_HANDLED); - std::priority_queue, Compare> openlist; - g_score_.at(start_index) = 0; - openlist.push(start_index); + return error_info; + } - std::vector neighbors_index; - int current_index, move_cost, h_score, count = 0; + ErrorInfo AStarPlanner::SearchPath(const int &start_index, + const int &goal_index, + std::vector &path) { + + g_score_.clear(); + f_score_.clear(); + parent_.clear(); + state_.clear(); + gridmap_width_ = costmap_ptr_->GetCostMap()->GetSizeXCell(); + gridmap_height_ = costmap_ptr_->GetCostMap()->GetSizeYCell(); + ROS_INFO("Search in a map %d", gridmap_width_*gridmap_height_); + cost_ = costmap_ptr_->GetCostMap()->GetCharMap(); + g_score_.resize(gridmap_height_ * gridmap_width_, std::numeric_limits::max()); + f_score_.resize(gridmap_height_ * gridmap_width_, std::numeric_limits::max()); + parent_.resize(gridmap_height_ * gridmap_width_, std::numeric_limits::max()); + state_.resize(gridmap_height_ * gridmap_width_, SearchState::NOT_HANDLED); + + std::priority_queue, Compare> openlist; + g_score_.at(start_index) = 0; + openlist.push(start_index); + + std::vector neighbors_index; + int current_index, move_cost, h_score, count = 0; + + while (!openlist.empty()) { + current_index = openlist.top(); + openlist.pop(); + state_.at(current_index) = SearchState::CLOSED; + + if (current_index == goal_index) { + ROS_INFO("Search takes %d cycle counts", count); + break; + } + + GetNineNeighbors(current_index, neighbors_index); + + for (auto neighbor_index : neighbors_index) { + + if (neighbor_index < 0 || + neighbor_index >= gridmap_height_ * gridmap_width_) { + continue; + } + + if (cost_[neighbor_index] >= inaccessible_cost_ || + state_.at(neighbor_index) == SearchState::CLOSED) { + continue; + } + + GetMoveCost(current_index, neighbor_index, move_cost); + + if (g_score_.at(neighbor_index) > g_score_.at(current_index) + move_cost + cost_[neighbor_index]) { + + g_score_.at(neighbor_index) = g_score_.at(current_index) + move_cost + cost_[neighbor_index]; + parent_.at(neighbor_index) = current_index; + + if (state_.at(neighbor_index) == SearchState::NOT_HANDLED) { + GetManhattanDistance(neighbor_index, goal_index, h_score); + f_score_.at(neighbor_index) = g_score_.at(neighbor_index) + h_score; + openlist.push(neighbor_index); + state_.at(neighbor_index) = SearchState::OPEN; + } + } + } + count++; + } - while (!openlist.empty()) { - current_index = openlist.top(); - openlist.pop(); - state_.at(current_index) = SearchState::CLOSED; + if (current_index != goal_index) { + ROS_WARN("Global planner can't search the valid path!"); + return ErrorInfo(ErrorCode::GP_PATH_SEARCH_ERROR, "Valid global path not found."); + } - if (current_index == goal_index) { - ROS_INFO("Search takes %d cycle counts", count); - break; - } + unsigned int iter_index = current_index, iter_x, iter_y; - GetNineNeighbors(current_index, neighbors_index); + geometry_msgs::PoseStamped iter_pos; + iter_pos.pose.orientation.w = 1; + iter_pos.header.frame_id = "map"; + path.clear(); + costmap_ptr_->GetCostMap()->Index2Cells(iter_index, iter_x, iter_y); + costmap_ptr_->GetCostMap()->Map2World(iter_x, iter_y, iter_pos.pose.position.x, iter_pos.pose.position.y); + path.push_back(iter_pos); - for (auto neighbor_index : neighbors_index) { + while (iter_index != start_index) { + iter_index = parent_.at(iter_index); +// if(cost_[iter_index]>= inaccessible_cost_){ +// LOG_INFO<<"Cost changes through planning for"<< static_cast(cost_[iter_index]); +// } + costmap_ptr_->GetCostMap()->Index2Cells(iter_index, iter_x, iter_y); + costmap_ptr_->GetCostMap()->Map2World(iter_x, iter_y, iter_pos.pose.position.x, iter_pos.pose.position.y); + path.push_back(iter_pos); + } - if (neighbor_index < 0 || - neighbor_index >= gridmap_height_ * gridmap_width_) { - continue; - } + std::reverse(path.begin(),path.end()); - if (cost_[neighbor_index] >= inaccessible_cost_ || - state_.at(neighbor_index) == SearchState::CLOSED) { - continue; - } + return ErrorInfo(ErrorCode::OK); - GetMoveCost(current_index, neighbor_index, move_cost); + } - if (g_score_.at(neighbor_index) > g_score_.at(current_index) + move_cost + cost_[neighbor_index]) { + ErrorInfo AStarPlanner::GetMoveCost(const int ¤t_index, + const int &neighbor_index, + int &move_cost) const { + if (abs(neighbor_index - current_index) == 1 || + abs(neighbor_index - current_index) == gridmap_width_) { + move_cost = 10; + } else if (abs(neighbor_index - current_index) == (gridmap_width_ + 1) || + abs(neighbor_index - current_index) == (gridmap_width_ - 1)) { + move_cost = 14; + } else { + return ErrorInfo(ErrorCode::GP_MOVE_COST_ERROR, + "Move cost can't be calculated cause current neighbor index is not accessible"); + } + return ErrorInfo(ErrorCode::OK); + } - g_score_.at(neighbor_index) = g_score_.at(current_index) + move_cost + cost_[neighbor_index]; - parent_.at(neighbor_index) = current_index; + void AStarPlanner::GetManhattanDistance(const int &index1, const int &index2, int &manhattan_distance) const { + manhattan_distance = heuristic_factor_* 10 * (abs(static_cast(index1 / gridmap_width_ - index2 / gridmap_width_)) + + abs(static_cast((index1 % gridmap_width_ - index2 % gridmap_width_)))); + } - if (state_.at(neighbor_index) == SearchState::NOT_HANDLED) { - GetManhattanDistance(neighbor_index, goal_index, h_score); - f_score_.at(neighbor_index) = g_score_.at(neighbor_index) + h_score; - openlist.push(neighbor_index); - state_.at(neighbor_index) = SearchState::OPEN; + void AStarPlanner::GetNineNeighbors(const int ¤t_index, std::vector &neighbors_index) const { + neighbors_index.clear(); + if(current_index - gridmap_width_ >= 0){ + neighbors_index.push_back(current_index - gridmap_width_); //up + } + if(current_index - gridmap_width_ - 1 >= 0 && (current_index - gridmap_width_ - 1 + 1) % gridmap_width_!= 0){ + neighbors_index.push_back(current_index - gridmap_width_ - 1); //left_up + } + if(current_index - 1 >= 0 && (current_index - 1 + 1) % gridmap_width_!= 0){ + neighbors_index.push_back(current_index - 1); //left + } + if(current_index + gridmap_width_ - 1 < gridmap_width_* gridmap_height_ + && (current_index + gridmap_width_ - 1 + 1) % gridmap_width_!= 0){ + neighbors_index.push_back(current_index + gridmap_width_ - 1); //left_down + } + if(current_index + gridmap_width_ < gridmap_width_* gridmap_height_){ + neighbors_index.push_back(current_index + gridmap_width_); //down + } + if(current_index + gridmap_width_ + 1 < gridmap_width_* gridmap_height_ + && (current_index + gridmap_width_ + 1 ) % gridmap_width_!= 0){ + neighbors_index.push_back(current_index + gridmap_width_ + 1); //right_down + } + if(current_index + 1 < gridmap_width_* gridmap_height_ + && (current_index + 1 ) % gridmap_width_!= 0) { + neighbors_index.push_back(current_index + 1); //right + } + if(current_index - gridmap_width_ + 1 >= 0 + && (current_index - gridmap_width_ + 1 ) % gridmap_width_!= 0) { + neighbors_index.push_back(current_index - gridmap_width_ + 1); //right_up } - } } - count++; - } - - if (current_index != goal_index) { - ROS_WARN("Global planner can't search the valid path!"); - return ErrorInfo(ErrorCode::GP_PATH_SEARCH_ERROR, "Valid global path not found."); - } - - unsigned int iter_index = current_index, iter_x, iter_y; - - geometry_msgs::PoseStamped iter_pos; - iter_pos.pose.orientation.w = 1; - iter_pos.header.frame_id = "map"; - path.clear(); - costmap_ptr_->GetCostMap()->Index2Cells(iter_index, iter_x, iter_y); - costmap_ptr_->GetCostMap()->Map2World(iter_x, iter_y, iter_pos.pose.position.x, iter_pos.pose.position.y); - path.push_back(iter_pos); - - while (iter_index != start_index) { - iter_index = parent_.at(iter_index); -// if(cost_[iter_index]>= inaccessible_cost_){ -// LOG_INFO<<"Cost changes through planning for"<< static_cast(cost_[iter_index]); -// } - costmap_ptr_->GetCostMap()->Index2Cells(iter_index, iter_x, iter_y); - costmap_ptr_->GetCostMap()->Map2World(iter_x, iter_y, iter_pos.pose.position.x, iter_pos.pose.position.y); - path.push_back(iter_pos); - } - - std::reverse(path.begin(),path.end()); - - return ErrorInfo(ErrorCode::OK); - -} - -ErrorInfo AStarPlanner::GetMoveCost(const int ¤t_index, - const int &neighbor_index, - int &move_cost) const { - if (abs(neighbor_index - current_index) == 1 || - abs(neighbor_index - current_index) == gridmap_width_) { - move_cost = 10; - } else if (abs(neighbor_index - current_index) == (gridmap_width_ + 1) || - abs(neighbor_index - current_index) == (gridmap_width_ - 1)) { - move_cost = 14; - } else { - return ErrorInfo(ErrorCode::GP_MOVE_COST_ERROR, - "Move cost can't be calculated cause current neighbor index is not accessible"); - } - return ErrorInfo(ErrorCode::OK); -} - -void AStarPlanner::GetManhattanDistance(const int &index1, const int &index2, int &manhattan_distance) const { - manhattan_distance = heuristic_factor_* 10 * (abs(index1 / gridmap_width_ - index2 / gridmap_width_) + - abs(index1 % gridmap_width_ - index2 % gridmap_width_)); -} - -void AStarPlanner::GetNineNeighbors(const int ¤t_index, std::vector &neighbors_index) const { - neighbors_index.clear(); - if(current_index - gridmap_width_ >= 0){ - neighbors_index.push_back(current_index - gridmap_width_); //up - } - if(current_index - gridmap_width_ - 1 >= 0 && (current_index - gridmap_width_ - 1 + 1) % gridmap_width_!= 0){ - neighbors_index.push_back(current_index - gridmap_width_ - 1); //left_up - } - if(current_index - 1 >= 0 && (current_index - 1 + 1) % gridmap_width_!= 0){ - neighbors_index.push_back(current_index - 1); //left - } - if(current_index + gridmap_width_ - 1 < gridmap_width_* gridmap_height_ - && (current_index + gridmap_width_ - 1 + 1) % gridmap_width_!= 0){ - neighbors_index.push_back(current_index + gridmap_width_ - 1); //left_down - } - if(current_index + gridmap_width_ < gridmap_width_* gridmap_height_){ - neighbors_index.push_back(current_index + gridmap_width_); //down - } - if(current_index + gridmap_width_ + 1 < gridmap_width_* gridmap_height_ - && (current_index + gridmap_width_ + 1 ) % gridmap_width_!= 0){ - neighbors_index.push_back(current_index + gridmap_width_ + 1); //right_down - } - if(current_index + 1 < gridmap_width_* gridmap_height_ - && (current_index + 1 ) % gridmap_width_!= 0) { - neighbors_index.push_back(current_index + 1); //right - } - if(current_index - gridmap_width_ + 1 >= 0 - && (current_index - gridmap_width_ + 1 ) % gridmap_width_!= 0) { - neighbors_index.push_back(current_index - gridmap_width_ + 1); //right_up - } -} } //namespace roborts_global_planner diff --git a/roborts_planning/global_planner/config/global_planner_config.prototxt b/roborts_planning/global_planner/config/global_planner_config.prototxt index 39a04d4b..72ab0319 100755 --- a/roborts_planning/global_planner/config/global_planner_config.prototxt +++ b/roborts_planning/global_planner/config/global_planner_config.prototxt @@ -1,5 +1,5 @@ - name: "a_star_planner" - selected_algorithm: "a_star_planner" + name: "spfa_planner" + selected_algorithm: "spfa_planner" frequency: 3 max_retries: 5 goal_distance_tolerance: 0.15 diff --git a/roborts_planning/global_planner/global_planner_algorithms.h b/roborts_planning/global_planner/global_planner_algorithms.h index 60bd2fa2..f82f9a1e 100755 --- a/roborts_planning/global_planner/global_planner_algorithms.h +++ b/roborts_planning/global_planner/global_planner_algorithms.h @@ -17,6 +17,6 @@ #ifndef ROBORTS_PLANNING_GLOBAL_PLANNER_GLOBAL_PLANNER_ALGORITHM_H #define ROBORTS_PLANNING_GLOBAL_PLANNER_GLOBAL_PLANNER_ALGORITHM_H -#include "a_star_planner/a_star_planner.h" +#include "spfa_planner/spfa_planner.h" -#endif // ROBORTS_PLANNING_GLOBAL_PLANNER_GLOBAL_PLANNER_ALGORITHM_H \ No newline at end of file +#endif // ROBORTS_PLANNING_GLOBAL_PLANNER_GLOBAL_PLANNER_ALGORITHM_H diff --git a/roborts_planning/local_planner/include/local_planner/line_iterator.h b/roborts_planning/local_planner/include/local_planner/line_iterator.h index 541d63a3..31d07f8b 100644 --- a/roborts_planning/local_planner/include/local_planner/line_iterator.h +++ b/roborts_planning/local_planner/include/local_planner/line_iterator.h @@ -43,8 +43,8 @@ class FastLineIterator { , y1_( y1 ) , x_( x0 ) , y_( y0 ) - , deltax_(abs(x1 - x0)) - , deltay_(abs(y1 - y0)) + , deltax_(abs(int(x1 - x0))) + , deltay_(abs(int(y1 - y0))) , curpixel_( 0 ) { xinc1_ = (x1 - x0) >0 ?1:-1; diff --git a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_acceleration_eage.h b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_acceleration_eage.h index 468e1b82..684849ef 100644 --- a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_acceleration_eage.h +++ b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_acceleration_eage.h @@ -60,7 +60,7 @@ #ifndef ROBORTS_PLANNING_LOCAL_PLANNER_TEB_ACCELERATION_EAGE_H #define ROBORTS_PLANNING_LOCAL_PLANNER_TEB_ACCELERATION_EAGE_H - +#include #include #include "local_planner/utility_tool.h" diff --git a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_base_eage.h b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_base_eage.h index db710174..9b9cd05b 100644 --- a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_base_eage.h +++ b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_base_eage.h @@ -60,7 +60,7 @@ #ifndef ROBORTS_PLANNING_LOCAL_PLANNER_TEB_BASE_EAGE_H #define ROBORTS_PLANNING_LOCAL_PLANNER_TEB_BASE_EAGE_H - +#include #include #include diff --git a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_kinematics_edge.h b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_kinematics_edge.h index c412b209..b1d462c6 100644 --- a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_kinematics_edge.h +++ b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_kinematics_edge.h @@ -60,7 +60,7 @@ #ifndef ROBORTS_PLANNING_LOCAL_PLANNER_TEB_KINEMATICS_EDGE_H #define ROBORTS_PLANNING_LOCAL_PLANNER_TEB_KINEMATICS_EDGE_H - +#include #include #include "timed_elastic_band/teb_vertex_pose.h" diff --git a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_local_planner.h b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_local_planner.h index 0b52569e..a3bd29ad 100644 --- a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_local_planner.h +++ b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_local_planner.h @@ -55,7 +55,7 @@ #ifndef ROBORTS_PLANNING_LOCAL_PLANNER_TEB_H #define ROBORTS_PLANNING_LOCAL_PLANNER_TEB_H - +#include #include #include "io/io.h" diff --git a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_obstacle_eage.h b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_obstacle_eage.h index 46f6d400..9d5a5b9e 100644 --- a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_obstacle_eage.h +++ b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_obstacle_eage.h @@ -60,6 +60,7 @@ #ifndef ROBORTS_PLANNING_LOCAL_PLANNER_TEB_OBSTACLE_EDGE_H #define ROBORTS_PLANNING_LOCAL_PLANNER_TEB_OBSTACLE_EDGE_H +#include #include "local_planner/obstacle.h" #include "local_planner/robot_footprint_model.h" #include "timed_elastic_band/teb_vertex_pose.h" diff --git a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_optimal.h b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_optimal.h index 0268455d..32abfaf4 100644 --- a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_optimal.h +++ b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_optimal.h @@ -56,6 +56,7 @@ #ifndef ROBORTS_PLANNING_LOCAL_PLANNER_TEB_OPTIMAL_H #define ROBORTS_PLANNING_LOCAL_PLANNER_TEB_OPTIMAL_H #include +#include #include #include diff --git a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_penalties.h b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_penalties.h index 07043c32..a1eace1e 100644 --- a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_penalties.h +++ b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_penalties.h @@ -55,7 +55,7 @@ #ifndef ROBORTS_PLANNING_LOCAL_PLANNER_TEB_PENALTIES_H #define ROBORTS_PLANNING_LOCAL_PLANNER_TEB_PENALTIES_H - +#include #include #include #include diff --git a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_prefer_rotdir_edge.h b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_prefer_rotdir_edge.h index d7936ca9..2d9a96de 100644 --- a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_prefer_rotdir_edge.h +++ b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_prefer_rotdir_edge.h @@ -60,7 +60,7 @@ #ifndef ROBORTS_PLANNING_LOCAL_PLANNER_TEB_PREFER_ROTDIR_EDGE_H #define ROBORTS_PLANNING_LOCAL_PLANNER_TEB_PREFER_ROTDIR_EDGE_H - +#include #include #include "timed_elastic_band/teb_vertex_pose.h" diff --git a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_time_optimal_eage.h b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_time_optimal_eage.h index a49db756..223eb99d 100644 --- a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_time_optimal_eage.h +++ b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_time_optimal_eage.h @@ -60,7 +60,7 @@ #ifndef ROBORTS_PLANNING_LOCAL_PLANNER_TEB_TIME_OPTIMAL_EDGE_H #define ROBORTS_PLANNING_LOCAL_PLANNER_TEB_TIME_OPTIMAL_EDGE_H - +#include #include #include diff --git a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_velocity_eage.h b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_velocity_eage.h index 06f75fe2..e83040ac 100644 --- a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_velocity_eage.h +++ b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_velocity_eage.h @@ -60,7 +60,7 @@ #ifndef ROBORTS_PLANNING_LOCAL_PLANNER_TEB_VELOCITY_EDGE_H #define ROBORTS_PLANNING_LOCAL_PLANNER_TEB_VELOCITY_EDGE_H - +#include #include diff --git a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_vertex_console.h b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_vertex_console.h index a9b368af..cac69361 100644 --- a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_vertex_console.h +++ b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_vertex_console.h @@ -55,7 +55,7 @@ #ifndef ROBORTS_PLANNING_LOCAL_PLANNER_TEB_VERTEX_CONSOLE_H #define ROBORTS_PLANNING_LOCAL_PLANNER_TEB_VERTEX_CONSOLE_H - +#include #include #include diff --git a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_vertex_pose.h b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_vertex_pose.h index 279c1c01..5940981f 100644 --- a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_vertex_pose.h +++ b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_vertex_pose.h @@ -60,7 +60,7 @@ #ifndef ROBORTS_PLANNING_LOCAL_PLANNER_TEB_VERTEX_POSE_H #define ROBORTS_PLANNING_LOCAL_PLANNER_TEB_VERTEX_POSE_H - +#include #include #include #include diff --git a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_vertex_timediff.h b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_vertex_timediff.h index e2ea697d..d8bc3996 100644 --- a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_vertex_timediff.h +++ b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_vertex_timediff.h @@ -60,7 +60,7 @@ #ifndef ROBORTS_PLANNING_LOCAL_PLANNER_TEB_VERTEX_TIMEDIFF_H #define ROBORTS_PLANNING_LOCAL_PLANNER_TEB_VERTEX_TIMEDIFF_H - +#include #include "g2o/config.h" #include "g2o/core/base_vertex.h" diff --git a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_via_point_edge.h b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_via_point_edge.h index b0e55bcf..ea4367b6 100644 --- a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_via_point_edge.h +++ b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/teb_via_point_edge.h @@ -60,7 +60,7 @@ #ifndef ROBORTS_PLANNING_LOCAL_PLANNER_TEB_VIA_POINT_EDGE_H #define ROBORTS_PLANNING_LOCAL_PLANNER_TEB_VIA_POINT_EDGE_H - +#include #include #include "timed_elastic_band/teb_vertex_pose.h" diff --git a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/timed_elastic_band.hpp b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/timed_elastic_band.hpp index 89b82ba0..c0637bb1 100644 --- a/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/timed_elastic_band.hpp +++ b/roborts_planning/local_planner/timed_elastic_band/include/timed_elastic_band/timed_elastic_band.hpp @@ -124,8 +124,8 @@ bool TebVertexConsole::InitTEBtoGoal(BidirIter path_start, Eigen::Vector2d diff_next = fun_position(*boost::next(path_start)) - curr_point; - double ang_diff = std::abs(g2o::normalize_theta(atan2(diff_next[1], diff_next[0]) - - atan2(diff_last[1], diff_last[0]))); + double ang_diff = std::abs(double(g2o::normalize_theta(atan2(diff_next[1], diff_next[0]) + - atan2(diff_last[1], diff_last[0])))); timestep_vel = ang_diff / max_vel_theta; if (max_acc_theta) { diff --git a/roborts_planning/local_planner/timed_elastic_band/src/teb_optimal.cpp b/roborts_planning/local_planner/timed_elastic_band/src/teb_optimal.cpp index 2ad24d72..8f27beb9 100644 --- a/roborts_planning/local_planner/timed_elastic_band/src/teb_optimal.cpp +++ b/roborts_planning/local_planner/timed_elastic_band/src/teb_optimal.cpp @@ -135,8 +135,8 @@ boost::shared_ptr TebOptimal::InitOptimizer() { boost::shared_ptr optimizer = boost::make_shared(); TebLinearSolver* linearSolver = new TebLinearSolver(); linearSolver->setBlockOrdering(true); - TebBlockSolver* blockSolver = new TebBlockSolver(linearSolver); - g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(blockSolver); + TebBlockSolver* blockSolver = new TebBlockSolver((std::unique_ptr >, std::default_delete > > >)linearSolver); + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg((std::unique_ptr)blockSolver); optimizer->setAlgorithm(solver); @@ -936,7 +936,7 @@ bool TebOptimal::IsHorizonReductionAppropriate(const std::vector &init return false; } - if ( std::abs(g2o::normalize_theta( vertex_console_.Pose(0).GetTheta() - vertex_console_.BackPose().GetTheta() ) ) > M_PI/2) { + if ( std::abs(double(g2o::normalize_theta( vertex_console_.Pose(0).GetTheta() - vertex_console_.BackPose().GetTheta() ) )) > M_PI/2) { return true; } diff --git a/roborts_planning/local_planner/timed_elastic_band/src/teb_vertex_console.cpp b/roborts_planning/local_planner/timed_elastic_band/src/teb_vertex_console.cpp index 748b72e4..f47777be 100644 --- a/roborts_planning/local_planner/timed_elastic_band/src/teb_vertex_console.cpp +++ b/roborts_planning/local_planner/timed_elastic_band/src/teb_vertex_console.cpp @@ -232,7 +232,7 @@ bool TebVertexConsole::InitTEBtoGoal(const DataBase &start, } double dist_to_goal = point_to_goal.norm(); - double no_steps_d = dist_to_goal / std::abs(diststep); + double no_steps_d = dist_to_goal / std::abs(double(diststep)); unsigned int no_steps = (unsigned int) std::floor(no_steps_d); if (max_vel_x > 0) { diff --git a/roborts_tracking/CMakeLists.txt b/roborts_tracking/CMakeLists.txt deleted file mode 100644 index 1c0ea4e4..00000000 --- a/roborts_tracking/CMakeLists.txt +++ /dev/null @@ -1,35 +0,0 @@ -cmake_minimum_required(VERSION 3.0) -project(roborts_tracking) -set(CMAKE_BUILD_TYPE Release) -find_package(OpenCV REQUIRED) -find_package(catkin REQUIRED COMPONENTS - roscpp - tf - roborts_msgs - ) - -if(NOT WIN32) - ADD_DEFINITIONS("-std=c++11") -endif(NOT WIN32) - -catkin_package() - -add_library(kcf_tracker STATIC - KCFcpp/src/fhog.cpp - KCFcpp/src/kcftracker.cpp) -target_link_libraries(kcf_tracker ${OpenCV_LIBRARIES}) -target_include_directories(kcf_tracker PRIVATE KCFcpp/src) - -add_executable(roborts_tracking_test - tracking_test.cpp - tracking_utility.cpp) -target_link_libraries(roborts_tracking_test - kcf_tracker - ${OpenCV_LIBS} - ${catkin_LIBRARIES}) -target_include_directories(roborts_tracking_test - PUBLIC - ${catkin_INCLUDE_DIRS}) -add_dependencies(roborts_tracking_test - roborts_msgs_generate_messages) - diff --git a/roborts_tracking/KCFcpp/CMakeLists.txt b/roborts_tracking/KCFcpp/CMakeLists.txt deleted file mode 100644 index bf1c0655..00000000 --- a/roborts_tracking/KCFcpp/CMakeLists.txt +++ /dev/null @@ -1,18 +0,0 @@ -cmake_minimum_required(VERSION 2.8) - -project(test) - -find_package(OpenCV REQUIRED) - -if(NOT WIN32) -ADD_DEFINITIONS("-std=c++0x -O3") -endif(NOT WIN32) - -include_directories(src) -FILE(GLOB_RECURSE sourcefiles "src/*.cpp") -add_executable( KCF ${sourcefiles} ) -target_link_libraries( KCF ${OpenCV_LIBS}) - - - - diff --git a/roborts_tracking/KCFcpp/KCFCpp.sh b/roborts_tracking/KCFcpp/KCFCpp.sh deleted file mode 100644 index a42afd51..00000000 --- a/roborts_tracking/KCFcpp/KCFCpp.sh +++ /dev/null @@ -1,3 +0,0 @@ - -KCF - diff --git a/roborts_tracking/KCFcpp/KCFLabCpp.sh b/roborts_tracking/KCFcpp/KCFLabCpp.sh deleted file mode 100644 index 2e2e6d29..00000000 --- a/roborts_tracking/KCFcpp/KCFLabCpp.sh +++ /dev/null @@ -1,3 +0,0 @@ - -KCF lab - diff --git a/roborts_tracking/KCFcpp/LICENSE b/roborts_tracking/KCFcpp/LICENSE deleted file mode 100644 index d9c1b318..00000000 --- a/roborts_tracking/KCFcpp/LICENSE +++ /dev/null @@ -1,28 +0,0 @@ -Copyright (c) 2015, Joao Faro -All rights reserved. - -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - -* Redistributions of source code must retain the above copyright notice, this - list of conditions and the following disclaimer. - -* Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - -* Neither the name of KCFcpp nor the names of its - contributors may be used to endorse or promote products derived from - this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE -FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL -DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, -OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE -OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - diff --git a/roborts_tracking/KCFcpp/README.md b/roborts_tracking/KCFcpp/README.md deleted file mode 100644 index 26e748a8..00000000 --- a/roborts_tracking/KCFcpp/README.md +++ /dev/null @@ -1,56 +0,0 @@ -# C++ KCF Tracker -This package includes a C++ class with several tracking methods based on the Kernelized Correlation Filter (KCF) [1, 2]. -It also includes an executable to interface with the VOT benchmark. - -[1] J. F. Henriques, R. Caseiro, P. Martins, J. Batista, -"High-Speed Tracking with Kernelized Correlation Filters", TPAMI 2015. - -[2] J. F. Henriques, R. Caseiro, P. Martins, J. Batista, -"Exploiting the Circulant Structure of Tracking-by-detection with Kernels", ECCV 2012. - - -Authors: Joao Faro, Christian Bailer, Joao F. Henriques -Contacts: joaopfaro@gmail.com, Christian.Bailer@dfki.de, henriques@isr.uc.pt -Institute of Systems and Robotics - University of Coimbra / Department of Augmented Vision DFKI - -### Algorithms (in this folder) ### - -"KCFC++", command: ./KCF -Description: KCF on HOG features, ported to C++ OpenCV. The original Matlab tracker placed 3rd in VOT 2014. - -"KCFLabC++", command: ./KCF lab -Description: KCF on HOG and Lab features, ported to C++ OpenCV. The Lab features are computed by quantizing CIE-Lab colors into 15 centroids, obtained from natural images by k-means. - -The CSK tracker [2] is also implemented as a bonus, simply by using raw grayscale as features (the filter becomes single-channel). - -### Compilation instructions ### -There are no external dependencies other than OpenCV 3.0.0. Tested on a freshly installed Ubuntu 14.04. - -1) cmake CMakeLists.txt -2) make - -### Running instructions ### - -The runtracker.cpp is prepared to be used with the VOT toolkit. The executable "KCF" should be called as: - -./KCF [OPTION_1] [OPTION_2] [...] - -Options available: - -gray - Use raw gray level features as in [1]. -hog - Use HOG features as in [2]. -lab - Use Lab colorspace features. This option will also enable HOG features by default. -singlescale - Performs single-scale detection, using a variable-size window. -fixed_window - Keep the window size fixed when in single-scale mode (multi-scale always used a fixed window). -show - Show the results in a window. - -To include it in your project, without the VOT toolkit you just need to: - - // Create the KCFTracker object with one of the available options - KCFTracker tracker(HOG, FIXEDWINDOW, MULTISCALE, LAB); - - // Give the first frame and the position of the object to the tracker - tracker.init( Rect(xMin, yMin, width, height), frame ); - - // Get the position of the object for the new frame - result = tracker.update(frame); diff --git a/roborts_tracking/KCFcpp/src/ffttools.hpp b/roborts_tracking/KCFcpp/src/ffttools.hpp deleted file mode 100644 index 8580a27c..00000000 --- a/roborts_tracking/KCFcpp/src/ffttools.hpp +++ /dev/null @@ -1,237 +0,0 @@ -/* -Author: Christian Bailer -Contact address: Christian.Bailer@dfki.de -Department Augmented Vision DFKI - - License Agreement - For Open Source Computer Vision Library - (3-clause BSD License) - -Redistribution and use in source and binary forms, with or without modification, -are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, - this list of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - * Neither the names of the copyright holders nor the names of the contributors - may be used to endorse or promote products derived from this software - without specific prior written permission. - -This software is provided by the copyright holders and contributors "as is" and -any express or implied warranties, including, but not limited to, the implied -warranties of merchantability and fitness for a particular purpose are disclaimed. -In no event shall copyright holders or contributors be liable for any direct, -indirect, incidental, special, exemplary, or consequential damages -(including, but not limited to, procurement of substitute goods or services; -loss of use, data, or profits; or business interruption) however caused -and on any theory of liability, whether in contract, strict liability, -or tort (including negligence or otherwise) arising in any way out of -the use of this software, even if advised of the possibility of such damage. -*/ - -#pragma once - -//#include - -#ifndef _OPENCV_FFTTOOLS_HPP_ -#define _OPENCV_FFTTOOLS_HPP_ -#endif - -//NOTE: FFTW support is still shaky, disabled for now. -/*#ifdef USE_FFTW -#include -#endif*/ - -namespace FFTTools -{ -// Previous declarations, to avoid warnings -cv::Mat fftd(cv::Mat img, bool backwards = false); -cv::Mat real(cv::Mat img); -cv::Mat imag(cv::Mat img); -cv::Mat magnitude(cv::Mat img); -cv::Mat complexMultiplication(cv::Mat a, cv::Mat b); -cv::Mat complexDivision(cv::Mat a, cv::Mat b); -void rearrange(cv::Mat &img); -void normalizedLogTransform(cv::Mat &img); - - -cv::Mat fftd(cv::Mat img, bool backwards) -{ -/* -#ifdef USE_FFTW - - fftw_complex * fm = (fftw_complex*) fftw_malloc(sizeof (fftw_complex) * img.cols * img.rows); - - fftw_plan p = fftw_plan_dft_2d(img.rows, img.cols, fm, fm, backwards ? 1 : -1, 0 * FFTW_ESTIMATE); - - - if (img.channels() == 1) - { - for (int i = 0; i < img.rows; i++) - for (int j = 0; j < img.cols; j++) - { - fm[i * img.cols + j][0] = img.at(i, j); - fm[i * img.cols + j][1] = 0; - } - } - else - { - assert(img.channels() == 2); - for (int i = 0; i < img.rows; i++) - for (int j = 0; j < img.cols; j++) - { - fm[i * img.cols + j][0] = img.at (i, j)[0]; - fm[i * img.cols + j][1] = img.at (i, j)[1]; - } - } - fftw_execute(p); - cv::Mat res(img.rows, img.cols, CV_64FC2); - - - for (int i = 0; i < img.rows; i++) - for (int j = 0; j < img.cols; j++) - { - res.at (i, j)[0] = fm[i * img.cols + j][0]; - res.at (i, j)[1] = fm[i * img.cols + j][1]; - - // _iout(fm[i * img.cols + j][0]); - } - - if (backwards)res *= 1.d / (float) (res.cols * res.rows); - - fftw_free(p); - fftw_free(fm); - return res; - -#else -*/ - if (img.channels() == 1) - { - cv::Mat planes[] = {cv::Mat_ (img), cv::Mat_::zeros(img.size())}; - //cv::Mat planes[] = {cv::Mat_ (img), cv::Mat_::zeros(img.size())}; - cv::merge(planes, 2, img); - } - cv::dft(img, img, backwards ? (cv::DFT_INVERSE | cv::DFT_SCALE) : 0 ); - - return img; - -/*#endif*/ - -} - -cv::Mat real(cv::Mat img) -{ - std::vector planes; - cv::split(img, planes); - return planes[0]; -} - -cv::Mat imag(cv::Mat img) -{ - std::vector planes; - cv::split(img, planes); - return planes[1]; -} - -cv::Mat magnitude(cv::Mat img) -{ - cv::Mat res; - std::vector planes; - cv::split(img, planes); // planes[0] = Re(DFT(I), planes[1] = Im(DFT(I)) - if (planes.size() == 1) res = cv::abs(img); - else if (planes.size() == 2) cv::magnitude(planes[0], planes[1], res); // planes[0] = magnitude - else assert(0); - return res; -} - -cv::Mat complexMultiplication(cv::Mat a, cv::Mat b) -{ - std::vector pa; - std::vector pb; - cv::split(a, pa); - cv::split(b, pb); - - std::vector pres; - pres.push_back(pa[0].mul(pb[0]) - pa[1].mul(pb[1])); - pres.push_back(pa[0].mul(pb[1]) + pa[1].mul(pb[0])); - - cv::Mat res; - cv::merge(pres, res); - - return res; -} - -cv::Mat complexDivision(cv::Mat a, cv::Mat b) -{ - std::vector pa; - std::vector pb; - cv::split(a, pa); - cv::split(b, pb); - - cv::Mat divisor = 1. / (pb[0].mul(pb[0]) + pb[1].mul(pb[1])); - - std::vector pres; - - pres.push_back((pa[0].mul(pb[0]) + pa[1].mul(pb[1])).mul(divisor)); - pres.push_back((pa[1].mul(pb[0]) + pa[0].mul(pb[1])).mul(divisor)); - - cv::Mat res; - cv::merge(pres, res); - return res; -} - -void rearrange(cv::Mat &img) -{ - // img = img(cv::Rect(0, 0, img.cols & -2, img.rows & -2)); - int cx = img.cols / 2; - int cy = img.rows / 2; - - cv::Mat q0(img, cv::Rect(0, 0, cx, cy)); // Top-Left - Create a ROI per quadrant - cv::Mat q1(img, cv::Rect(cx, 0, cx, cy)); // Top-Right - cv::Mat q2(img, cv::Rect(0, cy, cx, cy)); // Bottom-Left - cv::Mat q3(img, cv::Rect(cx, cy, cx, cy)); // Bottom-Right - - cv::Mat tmp; // swap quadrants (Top-Left with Bottom-Right) - q0.copyTo(tmp); - q3.copyTo(q0); - tmp.copyTo(q3); - q1.copyTo(tmp); // swap quadrant (Top-Right with Bottom-Left) - q2.copyTo(q1); - tmp.copyTo(q2); -} -/* -template < typename type> -cv::Mat fouriertransFull(const cv::Mat & in) -{ - return fftd(in); - - cv::Mat planes[] = {cv::Mat_ (in), cv::Mat_::zeros(in.size())}; - cv::Mat t; - assert(planes[0].depth() == planes[1].depth()); - assert(planes[0].size == planes[1].size); - cv::merge(planes, 2, t); - cv::dft(t, t); - - //cv::normalize(a, a, 0, 1, CV_MINMAX); - //cv::normalize(t, t, 0, 1, CV_MINMAX); - - // cv::imshow("a",real(a)); - // cv::imshow("b",real(t)); - // cv::waitKey(0); - - return t; -}*/ - -void normalizedLogTransform(cv::Mat &img) -{ - img = cv::abs(img); - img += cv::Scalar::all(1); - cv::log(img, img); - // cv::normalize(img, img, 0, 1, CV_MINMAX); -} - -} diff --git a/roborts_tracking/KCFcpp/src/fhog.cpp b/roborts_tracking/KCFcpp/src/fhog.cpp deleted file mode 100644 index 28898e83..00000000 --- a/roborts_tracking/KCFcpp/src/fhog.cpp +++ /dev/null @@ -1,511 +0,0 @@ -/*M/////////////////////////////////////////////////////////////////////////////////////// -// -// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. -// -// By downloading, copying, installing or using the software you agree to this license. -// If you do not agree to this license, do not download, install, -// copy or use the software. -// -// -// License Agreement -// For Open Source Computer Vision Library -// -// Copyright (C) 2010-2013, University of Nizhny Novgorod, all rights reserved. -// Third party copyrights are property of their respective owners. -// -// Redistribution and use in source and binary forms, with or without modification, -// are permitted provided that the following conditions are met: -// -// * Redistribution's of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// -// * Redistribution's in binary form must reproduce the above copyright notice, -// this list of conditions and the following disclaimer in the documentation -// and/or other materials provided with the distribution. -// -// * The name of the copyright holders may not be used to endorse or promote products -// derived from this software without specific prior written permission. -// -// This software is provided by the copyright holders and contributors "as is" and -// any express or implied warranties, including, but not limited to, the implied -// warranties of merchantability and fitness for a particular purpose are disclaimed. -// In no event shall the Intel Corporation or contributors be liable for any direct, -// indirect, incidental, special, exemplary, or consequential damages -// (including, but not limited to, procurement of substitute goods or services; -// loss of use, data, or profits; or business interruption) however caused -// and on any theory of liability, whether in contract, strict liability, -// or tort (including negligence or otherwise) arising in any way out of -// the use of this software, even if advised of the possibility of such damage. -// -//M*/ - - -//Modified from latentsvm module's "lsvmc_featurepyramid.cpp". - -//#include "precomp.hpp" -//#include "_lsvmc_latentsvm.h" -//#include "_lsvmc_resizeimg.h" - -#include "fhog.hpp" - - -#ifdef HAVE_TBB -#include -#include "tbb/parallel_for.h" -#include "tbb/blocked_range.h" -#endif - -#ifndef max -#define max(a,b) (((a) > (b)) ? (a) : (b)) -#endif - -#ifndef min -#define min(a,b) (((a) < (b)) ? (a) : (b)) -#endif - - -/* -// Getting feature map for the selected subimage -// -// API -// int getFeatureMaps(const IplImage * image, const int k, featureMap **map); -// INPUT -// image - selected subimage -// k - size of cells -// OUTPUT -// map - feature map -// RESULT -// Error status -*/ -int getFeatureMaps(const IplImage* image, const int k, CvLSVMFeatureMapCaskade **map) -{ - int sizeX, sizeY; - int p, px, stringSize; - int height, width, numChannels; - int i, j, kk, c, ii, jj, d; - float * datadx, * datady; - - int ch; - float magnitude, x, y, tx, ty; - - IplImage * dx, * dy; - int *nearest; - float *w, a_x, b_x; - - float kernel[3] = {-1.f, 0.f, 1.f}; - CvMat kernel_dx = cvMat(1, 3, CV_32F, kernel); - CvMat kernel_dy = cvMat(3, 1, CV_32F, kernel); - - float * r; - int * alfa; - - float boundary_x[NUM_SECTOR + 1]; - float boundary_y[NUM_SECTOR + 1]; - float max, dotProd; - int maxi; - - height = image->height; - width = image->width ; - - numChannels = image->nChannels; - - dx = cvCreateImage(cvSize(image->width, image->height), - IPL_DEPTH_32F, 3); - dy = cvCreateImage(cvSize(image->width, image->height), - IPL_DEPTH_32F, 3); - - sizeX = width / k; - sizeY = height / k; - px = 3 * NUM_SECTOR; - p = px; - stringSize = sizeX * p; - allocFeatureMapObject(map, sizeX, sizeY, p); - - cvFilter2D(image, dx, &kernel_dx, cvPoint(-1, 0)); - cvFilter2D(image, dy, &kernel_dy, cvPoint(0, -1)); - - float arg_vector; - for(i = 0; i <= NUM_SECTOR; i++) - { - arg_vector = ( (float) i ) * ( (float)(PI) / (float)(NUM_SECTOR) ); - boundary_x[i] = cosf(arg_vector); - boundary_y[i] = sinf(arg_vector); - }/*for(i = 0; i <= NUM_SECTOR; i++) */ - - r = (float *)malloc( sizeof(float) * (width * height)); - alfa = (int *)malloc( sizeof(int ) * (width * height * 2)); - - for(j = 1; j < height - 1; j++) - { - datadx = (float*)(dx->imageData + dx->widthStep * j); - datady = (float*)(dy->imageData + dy->widthStep * j); - for(i = 1; i < width - 1; i++) - { - c = 0; - x = (datadx[i * numChannels + c]); - y = (datady[i * numChannels + c]); - - r[j * width + i] =sqrtf(x * x + y * y); - for(ch = 1; ch < numChannels; ch++) - { - tx = (datadx[i * numChannels + ch]); - ty = (datady[i * numChannels + ch]); - magnitude = sqrtf(tx * tx + ty * ty); - if(magnitude > r[j * width + i]) - { - r[j * width + i] = magnitude; - c = ch; - x = tx; - y = ty; - } - }/*for(ch = 1; ch < numChannels; ch++)*/ - - max = boundary_x[0] * x + boundary_y[0] * y; - maxi = 0; - for (kk = 0; kk < NUM_SECTOR; kk++) - { - dotProd = boundary_x[kk] * x + boundary_y[kk] * y; - if (dotProd > max) - { - max = dotProd; - maxi = kk; - } - else - { - if (-dotProd > max) - { - max = -dotProd; - maxi = kk + NUM_SECTOR; - } - } - } - alfa[j * width * 2 + i * 2 ] = maxi % NUM_SECTOR; - alfa[j * width * 2 + i * 2 + 1] = maxi; - }/*for(i = 0; i < width; i++)*/ - }/*for(j = 0; j < height; j++)*/ - - nearest = (int *)malloc(sizeof(int ) * k); - w = (float*)malloc(sizeof(float) * (k * 2)); - - for(i = 0; i < k / 2; i++) - { - nearest[i] = -1; - }/*for(i = 0; i < k / 2; i++)*/ - for(i = k / 2; i < k; i++) - { - nearest[i] = 1; - }/*for(i = k / 2; i < k; i++)*/ - - for(j = 0; j < k / 2; j++) - { - b_x = k / 2 + j + 0.5f; - a_x = k / 2 - j - 0.5f; - w[j * 2 ] = 1.0f/a_x * ((a_x * b_x) / ( a_x + b_x)); - w[j * 2 + 1] = 1.0f/b_x * ((a_x * b_x) / ( a_x + b_x)); - }/*for(j = 0; j < k / 2; j++)*/ - for(j = k / 2; j < k; j++) - { - a_x = j - k / 2 + 0.5f; - b_x =-j + k / 2 - 0.5f + k; - w[j * 2 ] = 1.0f/a_x * ((a_x * b_x) / ( a_x + b_x)); - w[j * 2 + 1] = 1.0f/b_x * ((a_x * b_x) / ( a_x + b_x)); - }/*for(j = k / 2; j < k; j++)*/ - - for(i = 0; i < sizeY; i++) - { - for(j = 0; j < sizeX; j++) - { - for(ii = 0; ii < k; ii++) - { - for(jj = 0; jj < k; jj++) - { - if ((i * k + ii > 0) && - (i * k + ii < height - 1) && - (j * k + jj > 0) && - (j * k + jj < width - 1)) - { - d = (k * i + ii) * width + (j * k + jj); - (*map)->map[ i * stringSize + j * (*map)->numFeatures + alfa[d * 2 ]] += - r[d] * w[ii * 2] * w[jj * 2]; - (*map)->map[ i * stringSize + j * (*map)->numFeatures + alfa[d * 2 + 1] + NUM_SECTOR] += - r[d] * w[ii * 2] * w[jj * 2]; - if ((i + nearest[ii] >= 0) && - (i + nearest[ii] <= sizeY - 1)) - { - (*map)->map[(i + nearest[ii]) * stringSize + j * (*map)->numFeatures + alfa[d * 2 ] ] += - r[d] * w[ii * 2 + 1] * w[jj * 2 ]; - (*map)->map[(i + nearest[ii]) * stringSize + j * (*map)->numFeatures + alfa[d * 2 + 1] + NUM_SECTOR] += - r[d] * w[ii * 2 + 1] * w[jj * 2 ]; - } - if ((j + nearest[jj] >= 0) && - (j + nearest[jj] <= sizeX - 1)) - { - (*map)->map[i * stringSize + (j + nearest[jj]) * (*map)->numFeatures + alfa[d * 2 ] ] += - r[d] * w[ii * 2] * w[jj * 2 + 1]; - (*map)->map[i * stringSize + (j + nearest[jj]) * (*map)->numFeatures + alfa[d * 2 + 1] + NUM_SECTOR] += - r[d] * w[ii * 2] * w[jj * 2 + 1]; - } - if ((i + nearest[ii] >= 0) && - (i + nearest[ii] <= sizeY - 1) && - (j + nearest[jj] >= 0) && - (j + nearest[jj] <= sizeX - 1)) - { - (*map)->map[(i + nearest[ii]) * stringSize + (j + nearest[jj]) * (*map)->numFeatures + alfa[d * 2 ] ] += - r[d] * w[ii * 2 + 1] * w[jj * 2 + 1]; - (*map)->map[(i + nearest[ii]) * stringSize + (j + nearest[jj]) * (*map)->numFeatures + alfa[d * 2 + 1] + NUM_SECTOR] += - r[d] * w[ii * 2 + 1] * w[jj * 2 + 1]; - } - } - }/*for(jj = 0; jj < k; jj++)*/ - }/*for(ii = 0; ii < k; ii++)*/ - }/*for(j = 1; j < sizeX - 1; j++)*/ - }/*for(i = 1; i < sizeY - 1; i++)*/ - - cvReleaseImage(&dx); - cvReleaseImage(&dy); - - - free(w); - free(nearest); - - free(r); - free(alfa); - - return LATENT_SVM_OK; -} - -/* -// Feature map Normalization and Truncation -// -// API -// int normalizeAndTruncate(featureMap *map, const float alfa); -// INPUT -// map - feature map -// alfa - truncation threshold -// OUTPUT -// map - truncated and normalized feature map -// RESULT -// Error status -*/ -int normalizeAndTruncate(CvLSVMFeatureMapCaskade *map, const float alfa) -{ - int i,j, ii; - int sizeX, sizeY, p, pos, pp, xp, pos1, pos2; - float * partOfNorm; // norm of C(i, j) - float * newData; - float valOfNorm; - - sizeX = map->sizeX; - sizeY = map->sizeY; - partOfNorm = (float *)malloc (sizeof(float) * (sizeX * sizeY)); - - p = NUM_SECTOR; - xp = NUM_SECTOR * 3; - pp = NUM_SECTOR * 12; - - for(i = 0; i < sizeX * sizeY; i++) - { - valOfNorm = 0.0f; - pos = i * map->numFeatures; - for(j = 0; j < p; j++) - { - valOfNorm += map->map[pos + j] * map->map[pos + j]; - }/*for(j = 0; j < p; j++)*/ - partOfNorm[i] = valOfNorm; - }/*for(i = 0; i < sizeX * sizeY; i++)*/ - - sizeX -= 2; - sizeY -= 2; - - newData = (float *)malloc (sizeof(float) * (sizeX * sizeY * pp)); -//normalization - for(i = 1; i <= sizeY; i++) - { - for(j = 1; j <= sizeX; j++) - { - valOfNorm = sqrtf( - partOfNorm[(i )*(sizeX + 2) + (j )] + - partOfNorm[(i )*(sizeX + 2) + (j + 1)] + - partOfNorm[(i + 1)*(sizeX + 2) + (j )] + - partOfNorm[(i + 1)*(sizeX + 2) + (j + 1)]) + FLT_EPSILON; - pos1 = (i ) * (sizeX + 2) * xp + (j ) * xp; - pos2 = (i-1) * (sizeX ) * pp + (j-1) * pp; - for(ii = 0; ii < p; ii++) - { - newData[pos2 + ii ] = map->map[pos1 + ii ] / valOfNorm; - }/*for(ii = 0; ii < p; ii++)*/ - for(ii = 0; ii < 2 * p; ii++) - { - newData[pos2 + ii + p * 4] = map->map[pos1 + ii + p] / valOfNorm; - }/*for(ii = 0; ii < 2 * p; ii++)*/ - valOfNorm = sqrtf( - partOfNorm[(i )*(sizeX + 2) + (j )] + - partOfNorm[(i )*(sizeX + 2) + (j + 1)] + - partOfNorm[(i - 1)*(sizeX + 2) + (j )] + - partOfNorm[(i - 1)*(sizeX + 2) + (j + 1)]) + FLT_EPSILON; - for(ii = 0; ii < p; ii++) - { - newData[pos2 + ii + p ] = map->map[pos1 + ii ] / valOfNorm; - }/*for(ii = 0; ii < p; ii++)*/ - for(ii = 0; ii < 2 * p; ii++) - { - newData[pos2 + ii + p * 6] = map->map[pos1 + ii + p] / valOfNorm; - }/*for(ii = 0; ii < 2 * p; ii++)*/ - valOfNorm = sqrtf( - partOfNorm[(i )*(sizeX + 2) + (j )] + - partOfNorm[(i )*(sizeX + 2) + (j - 1)] + - partOfNorm[(i + 1)*(sizeX + 2) + (j )] + - partOfNorm[(i + 1)*(sizeX + 2) + (j - 1)]) + FLT_EPSILON; - for(ii = 0; ii < p; ii++) - { - newData[pos2 + ii + p * 2] = map->map[pos1 + ii ] / valOfNorm; - }/*for(ii = 0; ii < p; ii++)*/ - for(ii = 0; ii < 2 * p; ii++) - { - newData[pos2 + ii + p * 8] = map->map[pos1 + ii + p] / valOfNorm; - }/*for(ii = 0; ii < 2 * p; ii++)*/ - valOfNorm = sqrtf( - partOfNorm[(i )*(sizeX + 2) + (j )] + - partOfNorm[(i )*(sizeX + 2) + (j - 1)] + - partOfNorm[(i - 1)*(sizeX + 2) + (j )] + - partOfNorm[(i - 1)*(sizeX + 2) + (j - 1)]) + FLT_EPSILON; - for(ii = 0; ii < p; ii++) - { - newData[pos2 + ii + p * 3 ] = map->map[pos1 + ii ] / valOfNorm; - }/*for(ii = 0; ii < p; ii++)*/ - for(ii = 0; ii < 2 * p; ii++) - { - newData[pos2 + ii + p * 10] = map->map[pos1 + ii + p] / valOfNorm; - }/*for(ii = 0; ii < 2 * p; ii++)*/ - }/*for(j = 1; j <= sizeX; j++)*/ - }/*for(i = 1; i <= sizeY; i++)*/ -//truncation - for(i = 0; i < sizeX * sizeY * pp; i++) - { - if(newData [i] > alfa) newData [i] = alfa; - }/*for(i = 0; i < sizeX * sizeY * pp; i++)*/ -//swop data - - map->numFeatures = pp; - map->sizeX = sizeX; - map->sizeY = sizeY; - - free (map->map); - free (partOfNorm); - - map->map = newData; - - return LATENT_SVM_OK; -} -/* -// Feature map reduction -// In each cell we reduce dimension of the feature vector -// according to original paper special procedure -// -// API -// int PCAFeatureMaps(featureMap *map) -// INPUT -// map - feature map -// OUTPUT -// map - feature map -// RESULT -// Error status -*/ -int PCAFeatureMaps(CvLSVMFeatureMapCaskade *map) -{ - int i,j, ii, jj, k; - int sizeX, sizeY, p, pp, xp, yp, pos1, pos2; - float * newData; - float val; - float nx, ny; - - sizeX = map->sizeX; - sizeY = map->sizeY; - p = map->numFeatures; - pp = NUM_SECTOR * 3 + 4; - yp = 4; - xp = NUM_SECTOR; - - nx = 1.0f / sqrtf((float)(xp * 2)); - ny = 1.0f / sqrtf((float)(yp )); - - newData = (float *)malloc (sizeof(float) * (sizeX * sizeY * pp)); - - for(i = 0; i < sizeY; i++) - { - for(j = 0; j < sizeX; j++) - { - pos1 = ((i)*sizeX + j)*p; - pos2 = ((i)*sizeX + j)*pp; - k = 0; - for(jj = 0; jj < xp * 2; jj++) - { - val = 0; - for(ii = 0; ii < yp; ii++) - { - val += map->map[pos1 + yp * xp + ii * xp * 2 + jj]; - }/*for(ii = 0; ii < yp; ii++)*/ - newData[pos2 + k] = val * ny; - k++; - }/*for(jj = 0; jj < xp * 2; jj++)*/ - for(jj = 0; jj < xp; jj++) - { - val = 0; - for(ii = 0; ii < yp; ii++) - { - val += map->map[pos1 + ii * xp + jj]; - }/*for(ii = 0; ii < yp; ii++)*/ - newData[pos2 + k] = val * ny; - k++; - }/*for(jj = 0; jj < xp; jj++)*/ - for(ii = 0; ii < yp; ii++) - { - val = 0; - for(jj = 0; jj < 2 * xp; jj++) - { - val += map->map[pos1 + yp * xp + ii * xp * 2 + jj]; - }/*for(jj = 0; jj < xp; jj++)*/ - newData[pos2 + k] = val * nx; - k++; - } /*for(ii = 0; ii < yp; ii++)*/ - }/*for(j = 0; j < sizeX; j++)*/ - }/*for(i = 0; i < sizeY; i++)*/ -//swop data - - map->numFeatures = pp; - - free (map->map); - - map->map = newData; - - return LATENT_SVM_OK; -} - - -//modified from "lsvmc_routine.cpp" - -int allocFeatureMapObject(CvLSVMFeatureMapCaskade **obj, const int sizeX, - const int sizeY, const int numFeatures) -{ - int i; - (*obj) = (CvLSVMFeatureMapCaskade *)malloc(sizeof(CvLSVMFeatureMapCaskade)); - (*obj)->sizeX = sizeX; - (*obj)->sizeY = sizeY; - (*obj)->numFeatures = numFeatures; - (*obj)->map = (float *) malloc(sizeof (float) * - (sizeX * sizeY * numFeatures)); - for(i = 0; i < sizeX * sizeY * numFeatures; i++) - { - (*obj)->map[i] = 0.0f; - } - return LATENT_SVM_OK; -} - -int freeFeatureMapObject (CvLSVMFeatureMapCaskade **obj) -{ - if(*obj == NULL) return LATENT_SVM_MEM_NULL; - free((*obj)->map); - free(*obj); - (*obj) = NULL; - return LATENT_SVM_OK; -} diff --git a/roborts_tracking/KCFcpp/src/fhog.hpp b/roborts_tracking/KCFcpp/src/fhog.hpp deleted file mode 100644 index 060bfec6..00000000 --- a/roborts_tracking/KCFcpp/src/fhog.hpp +++ /dev/null @@ -1,178 +0,0 @@ -/*M/////////////////////////////////////////////////////////////////////////////////////// -// -// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. -// -// By downloading, copying, installing or using the software you agree to this license. -// If you do not agree to this license, do not download, install, -// copy or use the software. -// -// -// License Agreement -// For Open Source Computer Vision Library -// -// Copyright (C) 2010-2013, University of Nizhny Novgorod, all rights reserved. -// Third party copyrights are property of their respective owners. -// -// Redistribution and use in source and binary forms, with or without modification, -// are permitted provided that the following conditions are met: -// -// * Redistribution's of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// -// * Redistribution's in binary form must reproduce the above copyright notice, -// this list of conditions and the following disclaimer in the documentation -// and/or other materials provided with the distribution. -// -// * The name of the copyright holders may not be used to endorse or promote products -// derived from this software without specific prior written permission. -// -// This software is provided by the copyright holders and contributors "as is" and -// any express or implied warranties, including, but not limited to, the implied -// warranties of merchantability and fitness for a particular purpose are disclaimed. -// In no event shall the Intel Corporation or contributors be liable for any direct, -// indirect, incidental, special, exemplary, or consequential damages -// (including, but not limited to, procurement of substitute goods or services; -// loss of use, data, or profits; or business interruption) however caused -// and on any theory of liability, whether in contract, strict liability, -// or tort (including negligence or otherwise) arising in any way out of -// the use of this software, even if advised of the possibility of such damage. -// -//M*/ - - -//Modified from latentsvm module's "_lsvmc_latentsvm.h". - - -/*****************************************************************************/ -/* Latent SVM prediction API */ -/*****************************************************************************/ - -#ifndef _FHOG_H_ -#define _FHOG_H_ - -#include -//#include "_lsvmc_types.h" -//#include "_lsvmc_error.h" -//#include "_lsvmc_routine.h" - -//#include "opencv2/imgproc.hpp" -#include "opencv2/imgproc/imgproc_c.h" - - -//modified from "_lsvmc_types.h" - -// DataType: STRUCT featureMap -// FEATURE MAP DESCRIPTION -// Rectangular map (sizeX x sizeY), -// every cell stores feature vector (dimension = numFeatures) -// map - matrix of feature vectors -// to set and get feature vectors (i,j) -// used formula map[(j * sizeX + i) * p + k], where -// k - component of feature vector in cell (i, j) -typedef struct{ - int sizeX; - int sizeY; - int numFeatures; - float *map; -} CvLSVMFeatureMapCaskade; - - -#include "float.h" - -#define PI CV_PI - -#define EPS 0.000001 - -#define F_MAX FLT_MAX -#define F_MIN -FLT_MAX - -// The number of elements in bin -// The number of sectors in gradient histogram building -#define NUM_SECTOR 9 - -// The number of levels in image resize procedure -// We need Lambda levels to resize image twice -#define LAMBDA 10 - -// Block size. Used in feature pyramid building procedure -#define SIDE_LENGTH 8 - -#define VAL_OF_TRUNCATE 0.2f - - -//modified from "_lsvm_error.h" -#define LATENT_SVM_OK 0 -#define LATENT_SVM_MEM_NULL 2 -#define DISTANCE_TRANSFORM_OK 1 -#define DISTANCE_TRANSFORM_GET_INTERSECTION_ERROR -1 -#define DISTANCE_TRANSFORM_ERROR -2 -#define DISTANCE_TRANSFORM_EQUAL_POINTS -3 -#define LATENT_SVM_GET_FEATURE_PYRAMID_FAILED -4 -#define LATENT_SVM_SEARCH_OBJECT_FAILED -5 -#define LATENT_SVM_FAILED_SUPERPOSITION -6 -#define FILTER_OUT_OF_BOUNDARIES -7 -#define LATENT_SVM_TBB_SCHEDULE_CREATION_FAILED -8 -#define LATENT_SVM_TBB_NUMTHREADS_NOT_CORRECT -9 -#define FFT_OK 2 -#define FFT_ERROR -10 -#define LSVM_PARSER_FILE_NOT_FOUND -11 - - - -/* -// Getting feature map for the selected subimage -// -// API -// int getFeatureMaps(const IplImage * image, const int k, featureMap **map); -// INPUT -// image - selected subimage -// k - size of cells -// OUTPUT -// map - feature map -// RESULT -// Error status -*/ -int getFeatureMaps(const IplImage * image, const int k, CvLSVMFeatureMapCaskade **map); - - -/* -// Feature map Normalization and Truncation -// -// API -// int normalizationAndTruncationFeatureMaps(featureMap *map, const float alfa); -// INPUT -// map - feature map -// alfa - truncation threshold -// OUTPUT -// map - truncated and normalized feature map -// RESULT -// Error status -*/ -int normalizeAndTruncate(CvLSVMFeatureMapCaskade *map, const float alfa); - -/* -// Feature map reduction -// In each cell we reduce dimension of the feature vector -// according to original paper special procedure -// -// API -// int PCAFeatureMaps(featureMap *map) -// INPUT -// map - feature map -// OUTPUT -// map - feature map -// RESULT -// Error status -*/ -int PCAFeatureMaps(CvLSVMFeatureMapCaskade *map); - - -//modified from "lsvmc_routine.h" - -int allocFeatureMapObject(CvLSVMFeatureMapCaskade **obj, const int sizeX, const int sizeY, - const int p); - -int freeFeatureMapObject (CvLSVMFeatureMapCaskade **obj); - - -#endif diff --git a/roborts_tracking/KCFcpp/src/kcftracker.cpp b/roborts_tracking/KCFcpp/src/kcftracker.cpp deleted file mode 100644 index 7012f973..00000000 --- a/roborts_tracking/KCFcpp/src/kcftracker.cpp +++ /dev/null @@ -1,519 +0,0 @@ -/* - -Tracker based on Kernelized Correlation Filter (KCF) [1] and Circulant Structure with Kernels (CSK) [2]. -CSK is implemented by using raw gray level features, since it is a single-channel filter. -KCF is implemented by using HOG features (the default), since it extends CSK to multiple channels. - -[1] J. F. Henriques, R. Caseiro, P. Martins, J. Batista, -"High-Speed Tracking with Kernelized Correlation Filters", TPAMI 2015. - -[2] J. F. Henriques, R. Caseiro, P. Martins, J. Batista, -"Exploiting the Circulant Structure of Tracking-by-detection with Kernels", ECCV 2012. - -Authors: Joao Faro, Christian Bailer, Joao F. Henriques -Contacts: joaopfaro@gmail.com, Christian.Bailer@dfki.de, henriques@isr.uc.pt -Institute of Systems and Robotics - University of Coimbra / Department Augmented Vision DFKI - - -Constructor parameters, all boolean: - hog: use HOG features (default), otherwise use raw pixels - fixed_window: fix window size (default), otherwise use ROI size (slower but more accurate) - multiscale: use multi-scale tracking (default; cannot be used with fixed_window = true) - -Default values are set for all properties of the tracker depending on the above choices. -Their values can be customized further before calling init(): - interp_factor: linear interpolation factor for adaptation - sigma: gaussian kernel bandwidth - lambda: regularization - cell_size: HOG cell size - padding: area surrounding the target, relative to its size - output_sigma_factor: bandwidth of gaussian target - template_size: template size in pixels, 0 to use ROI size - scale_step: scale step for multi-scale estimation, 1 to disable it - scale_weight: to downweight detection scores of other scales for added stability - -For speed, the value (template_size/cell_size) should be a power of 2 or a product of small prime numbers. - -Inputs to init(): - image is the initial frame. - roi is a cv::Rect with the target positions in the initial frame - -Inputs to update(): - image is the current frame. - -Outputs of update(): - cv::Rect with target positions for the current frame - - -By downloading, copying, installing or using the software you agree to this license. -If you do not agree to this license, do not download, install, -copy or use the software. - - - License Agreement - For Open Source Computer Vision Library - (3-clause BSD License) - -Redistribution and use in source and binary forms, with or without modification, -are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, - this list of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - * Neither the names of the copyright holders nor the names of the contributors - may be used to endorse or promote products derived from this software - without specific prior written permission. - -This software is provided by the copyright holders and contributors "as is" and -any express or implied warranties, including, but not limited to, the implied -warranties of merchantability and fitness for a particular purpose are disclaimed. -In no event shall copyright holders or contributors be liable for any direct, -indirect, incidental, special, exemplary, or consequential damages -(including, but not limited to, procurement of substitute goods or services; -loss of use, data, or profits; or business interruption) however caused -and on any theory of liability, whether in contract, strict liability, -or tort (including negligence or otherwise) arising in any way out of -the use of this software, even if advised of the possibility of such damage. - */ - -#ifndef _KCFTRACKER_HEADERS -#include "kcftracker.hpp" -#include "ffttools.hpp" -#include "recttools.hpp" -#include "fhog.hpp" -#include "labdata.hpp" -#endif - -// Constructor -KCFTracker::KCFTracker(bool hog, bool fixed_window, bool multiscale, bool lab) -{ - - // Parameters equal in all cases - lambda = 0.0001; - padding = 2.5; - //output_sigma_factor = 0.1; - output_sigma_factor = 0.125; - - - if (hog) { // HOG - // VOT - interp_factor = 0.012; - sigma = 0.6; - // TPAMI - //interp_factor = 0.02; - //sigma = 0.5; - cell_size = 4; - _hogfeatures = true; - - if (lab) { - interp_factor = 0.005; - sigma = 0.4; - //output_sigma_factor = 0.025; - output_sigma_factor = 0.1; - - _labfeatures = true; - _labCentroids = cv::Mat(nClusters, 3, CV_32FC1, &data); - cell_sizeQ = cell_size*cell_size; - } - else{ - _labfeatures = false; - } - } - else { // RAW - interp_factor = 0.075; - sigma = 0.2; - cell_size = 1; - _hogfeatures = false; - - if (lab) { - printf("Lab features are only used with HOG features.\n"); - _labfeatures = false; - } - } - - - if (multiscale) { // multiscale - template_size = 96; - //template_size = 100; - scale_step = 1.05; - scale_weight = 0.95; - if (!fixed_window) { - //printf("Multiscale does not support non-fixed window.\n"); - fixed_window = true; - } - } - else if (fixed_window) { // fit correction without multiscale - template_size = 96; - //template_size = 100; - scale_step = 1; - } - else { - template_size = 1; - scale_step = 1; - } -} - -// Initialize tracker -void KCFTracker::init(const cv::Rect &roi, cv::Mat image) -{ - _roi = roi; - assert(roi.width >= 0 && roi.height >= 0); - _tmpl = getFeatures(image, 1); - _prob = createGaussianPeak(size_patch[0], size_patch[1]); - _alphaf = cv::Mat(size_patch[0], size_patch[1], CV_32FC2, float(0)); - //_num = cv::Mat(size_patch[0], size_patch[1], CV_32FC2, float(0)); - //_den = cv::Mat(size_patch[0], size_patch[1], CV_32FC2, float(0)); - train(_tmpl, 1.0); // train with initial frame - } -// Update position based on the new frame -cv::Rect KCFTracker::update(cv::Mat image) -{ - if (_roi.x + _roi.width <= 0) _roi.x = -_roi.width + 1; - if (_roi.y + _roi.height <= 0) _roi.y = -_roi.height + 1; - if (_roi.x >= image.cols - 1) _roi.x = image.cols - 2; - if (_roi.y >= image.rows - 1) _roi.y = image.rows - 2; - - float cx = _roi.x + _roi.width / 2.0f; - float cy = _roi.y + _roi.height / 2.0f; - - - float peak_value; - cv::Point2f res = detect(_tmpl, getFeatures(image, 0, 1.0f), peak_value); - - if (scale_step != 1) { - // Test at a smaller _scale - float new_peak_value; - cv::Point2f new_res = detect(_tmpl, getFeatures(image, 0, 1.0f / scale_step), new_peak_value); - - if (scale_weight * new_peak_value > peak_value) { - res = new_res; - peak_value = new_peak_value; - _scale /= scale_step; - _roi.width /= scale_step; - _roi.height /= scale_step; - } - - // Test at a bigger _scale - new_res = detect(_tmpl, getFeatures(image, 0, scale_step), new_peak_value); - - if (scale_weight * new_peak_value > peak_value) { - res = new_res; - peak_value = new_peak_value; - _scale *= scale_step; - _roi.width *= scale_step; - _roi.height *= scale_step; - } - } - - // Adjust by cell size and _scale - _roi.x = cx - _roi.width / 2.0f + ((float) res.x * cell_size * _scale); - _roi.y = cy - _roi.height / 2.0f + ((float) res.y * cell_size * _scale); - - if (_roi.x >= image.cols - 1) _roi.x = image.cols - 1; - if (_roi.y >= image.rows - 1) _roi.y = image.rows - 1; - if (_roi.x + _roi.width <= 0) _roi.x = -_roi.width + 2; - if (_roi.y + _roi.height <= 0) _roi.y = -_roi.height + 2; - - assert(_roi.width >= 0 && _roi.height >= 0); - cv::Mat x = getFeatures(image, 0); - train(x, interp_factor); - - return _roi; -} - - -// Detect object in the current frame. -cv::Point2f KCFTracker::detect(cv::Mat z, cv::Mat x, float &peak_value) -{ - using namespace FFTTools; - - cv::Mat k = gaussianCorrelation(x, z); - cv::Mat res = (real(fftd(complexMultiplication(_alphaf, fftd(k)), true))); - - //minMaxLoc only accepts doubles for the peak, and integer points for the coordinates - cv::Point2i pi; - double pv; - cv::minMaxLoc(res, NULL, &pv, NULL, &pi); - peak_value = (float) pv; - - //subpixel peak estimation, coordinates will be non-integer - cv::Point2f p((float)pi.x, (float)pi.y); - - if (pi.x > 0 && pi.x < res.cols-1) { - p.x += subPixelPeak(res.at(pi.y, pi.x-1), peak_value, res.at(pi.y, pi.x+1)); - } - - if (pi.y > 0 && pi.y < res.rows-1) { - p.y += subPixelPeak(res.at(pi.y-1, pi.x), peak_value, res.at(pi.y+1, pi.x)); - } - - p.x -= (res.cols) / 2; - p.y -= (res.rows) / 2; - - return p; -} - -// train tracker with a single image -void KCFTracker::train(cv::Mat x, float train_interp_factor) -{ - using namespace FFTTools; - - cv::Mat k = gaussianCorrelation(x, x); - cv::Mat alphaf = complexDivision(_prob, (fftd(k) + lambda)); - - _tmpl = (1 - train_interp_factor) * _tmpl + (train_interp_factor) * x; - _alphaf = (1 - train_interp_factor) * _alphaf + (train_interp_factor) * alphaf; - - - /*cv::Mat kf = fftd(gaussianCorrelation(x, x)); - cv::Mat num = complexMultiplication(kf, _prob); - cv::Mat den = complexMultiplication(kf, kf + lambda); - - _tmpl = (1 - train_interp_factor) * _tmpl + (train_interp_factor) * x; - _num = (1 - train_interp_factor) * _num + (train_interp_factor) * num; - _den = (1 - train_interp_factor) * _den + (train_interp_factor) * den; - - _alphaf = complexDivision(_num, _den);*/ - -} - -// Evaluates a Gaussian kernel with bandwidth SIGMA for all relative shifts between input images X and Y, which must both be MxN. They must also be periodic (ie., pre-processed with a cosine window). -cv::Mat KCFTracker::gaussianCorrelation(cv::Mat x1, cv::Mat x2) -{ - using namespace FFTTools; - cv::Mat c = cv::Mat( cv::Size(size_patch[1], size_patch[0]), CV_32F, cv::Scalar(0) ); - // HOG features - if (_hogfeatures) { - cv::Mat caux; - cv::Mat x1aux; - cv::Mat x2aux; - for (int i = 0; i < size_patch[2]; i++) { - x1aux = x1.row(i); // Procedure do deal with cv::Mat multichannel bug - x1aux = x1aux.reshape(1, size_patch[0]); - x2aux = x2.row(i).reshape(1, size_patch[0]); - cv::mulSpectrums(fftd(x1aux), fftd(x2aux), caux, 0, true); - caux = fftd(caux, true); - rearrange(caux); - caux.convertTo(caux,CV_32F); - c = c + real(caux); - } - } - // Gray features - else { - cv::mulSpectrums(fftd(x1), fftd(x2), c, 0, true); - c = fftd(c, true); - rearrange(c); - c = real(c); - } - cv::Mat d; - cv::max(( (cv::sum(x1.mul(x1))[0] + cv::sum(x2.mul(x2))[0])- 2. * c) / (size_patch[0]*size_patch[1]*size_patch[2]) , 0, d); - - cv::Mat k; - cv::exp((-d / (sigma * sigma)), k); - return k; -} - -// Create Gaussian Peak. Function called only in the first frame. -cv::Mat KCFTracker::createGaussianPeak(int sizey, int sizex) -{ - cv::Mat_ res(sizey, sizex); - - int syh = (sizey) / 2; - int sxh = (sizex) / 2; - - float output_sigma = std::sqrt((float) sizex * sizey) / padding * output_sigma_factor; - float mult = -0.5 / (output_sigma * output_sigma); - - for (int i = 0; i < sizey; i++) - for (int j = 0; j < sizex; j++) - { - int ih = i - syh; - int jh = j - sxh; - res(i, j) = std::exp(mult * (float) (ih * ih + jh * jh)); - } - return FFTTools::fftd(res); -} - -// Obtain sub-window from image, with replication-padding and extract features -cv::Mat KCFTracker::getFeatures(const cv::Mat & image, bool inithann, float scale_adjust) -{ - cv::Rect extracted_roi; - - float cx = _roi.x + _roi.width / 2; - float cy = _roi.y + _roi.height / 2; - - if (inithann) { - int padded_w = _roi.width * padding; - int padded_h = _roi.height * padding; - - if (template_size > 1) { // Fit largest dimension to the given template size - if (padded_w >= padded_h) //fit to width - _scale = padded_w / (float) template_size; - else - _scale = padded_h / (float) template_size; - - _tmpl_sz.width = padded_w / _scale; - _tmpl_sz.height = padded_h / _scale; - } - else { //No template size given, use ROI size - _tmpl_sz.width = padded_w; - _tmpl_sz.height = padded_h; - _scale = 1; - // original code from paper: - /*if (sqrt(padded_w * padded_h) >= 100) { //Normal size - _tmpl_sz.width = padded_w; - _tmpl_sz.height = padded_h; - _scale = 1; - } - else { //ROI is too big, track at half size - _tmpl_sz.width = padded_w / 2; - _tmpl_sz.height = padded_h / 2; - _scale = 2; - }*/ - } - - if (_hogfeatures) { - // Round to cell size and also make it even - _tmpl_sz.width = ( ( (int)(_tmpl_sz.width / (2 * cell_size)) ) * 2 * cell_size ) + cell_size*2; - _tmpl_sz.height = ( ( (int)(_tmpl_sz.height / (2 * cell_size)) ) * 2 * cell_size ) + cell_size*2; - } - else { //Make number of pixels even (helps with some logic involving half-dimensions) - _tmpl_sz.width = (_tmpl_sz.width / 2) * 2; - _tmpl_sz.height = (_tmpl_sz.height / 2) * 2; - } - } - - extracted_roi.width = scale_adjust * _scale * _tmpl_sz.width; - extracted_roi.height = scale_adjust * _scale * _tmpl_sz.height; - - // center roi with new size - extracted_roi.x = cx - extracted_roi.width / 2; - extracted_roi.y = cy - extracted_roi.height / 2; - - cv::Mat FeaturesMap; - cv::Mat z = RectTools::subwindow(image, extracted_roi, cv::BORDER_REPLICATE); - - if (z.cols != _tmpl_sz.width || z.rows != _tmpl_sz.height) { - cv::resize(z, z, _tmpl_sz); - } - - // HOG features - if (_hogfeatures) { - IplImage z_ipl = z; - CvLSVMFeatureMapCaskade *map; - getFeatureMaps(&z_ipl, cell_size, &map); - normalizeAndTruncate(map,0.2f); - PCAFeatureMaps(map); - size_patch[0] = map->sizeY; - size_patch[1] = map->sizeX; - size_patch[2] = map->numFeatures; - - FeaturesMap = cv::Mat(cv::Size(map->numFeatures,map->sizeX*map->sizeY), CV_32F, map->map); // Procedure do deal with cv::Mat multichannel bug - FeaturesMap = FeaturesMap.t(); - freeFeatureMapObject(&map); - - // Lab features - if (_labfeatures) { - cv::Mat imgLab; - cvtColor(z, imgLab, CV_BGR2Lab); - unsigned char *input = (unsigned char*)(imgLab.data); - - // Sparse output vector - cv::Mat outputLab = cv::Mat(_labCentroids.rows, size_patch[0]*size_patch[1], CV_32F, float(0)); - - int cntCell = 0; - // Iterate through each cell - for (int cY = cell_size; cY < z.rows-cell_size; cY+=cell_size){ - for (int cX = cell_size; cX < z.cols-cell_size; cX+=cell_size){ - // Iterate through each pixel of cell (cX,cY) - for(int y = cY; y < cY+cell_size; ++y){ - for(int x = cX; x < cX+cell_size; ++x){ - // Lab components for each pixel - float l = (float)input[(z.cols * y + x) * 3]; - float a = (float)input[(z.cols * y + x) * 3 + 1]; - float b = (float)input[(z.cols * y + x) * 3 + 2]; - - // Iterate trough each centroid - float minDist = FLT_MAX; - int minIdx = 0; - float *inputCentroid = (float*)(_labCentroids.data); - for(int k = 0; k < _labCentroids.rows; ++k){ - float dist = ( (l - inputCentroid[3*k]) * (l - inputCentroid[3*k]) ) - + ( (a - inputCentroid[3*k+1]) * (a - inputCentroid[3*k+1]) ) - + ( (b - inputCentroid[3*k+2]) * (b - inputCentroid[3*k+2]) ); - if(dist < minDist){ - minDist = dist; - minIdx = k; - } - } - // Store result at output - outputLab.at(minIdx, cntCell) += 1.0 / cell_sizeQ; - //((float*) outputLab.data)[minIdx * (size_patch[0]*size_patch[1]) + cntCell] += 1.0 / cell_sizeQ; - } - } - cntCell++; - } - } - // Update size_patch[2] and add features to FeaturesMap - size_patch[2] += _labCentroids.rows; - FeaturesMap.push_back(outputLab); - } - } - else { - FeaturesMap = RectTools::getGrayImage(z); - FeaturesMap -= (float) 0.5; // In Paper; - size_patch[0] = z.rows; - size_patch[1] = z.cols; - size_patch[2] = 1; - } - - if (inithann) { - createHanningMats(); - } - FeaturesMap = hann.mul(FeaturesMap); - return FeaturesMap; -} - -// Initialize Hanning window. Function called only in the first frame. -void KCFTracker::createHanningMats() -{ - cv::Mat hann1t = cv::Mat(cv::Size(size_patch[1],1), CV_32F, cv::Scalar(0)); - cv::Mat hann2t = cv::Mat(cv::Size(1,size_patch[0]), CV_32F, cv::Scalar(0)); - - for (int i = 0; i < hann1t.cols; i++) - hann1t.at (0, i) = 0.5 * (1 - std::cos(2 * 3.14159265358979323846 * i / (hann1t.cols - 1))); - for (int i = 0; i < hann2t.rows; i++) - hann2t.at (i, 0) = 0.5 * (1 - std::cos(2 * 3.14159265358979323846 * i / (hann2t.rows - 1))); - - cv::Mat hann2d = hann2t * hann1t; - // HOG features - if (_hogfeatures) { - cv::Mat hann1d = hann2d.reshape(1,1); // Procedure do deal with cv::Mat multichannel bug - - hann = cv::Mat(cv::Size(size_patch[0]*size_patch[1], size_patch[2]), CV_32F, cv::Scalar(0)); - for (int i = 0; i < size_patch[2]; i++) { - for (int j = 0; j(i,j) = hann1d.at(0,j); - } - } - } - // Gray features - else { - hann = hann2d; - } -} - -// Calculate sub-pixel peak for one dimension -float KCFTracker::subPixelPeak(float left, float center, float right) -{ - float divisor = 2 * center - right - left; - - if (divisor == 0) - return 0; - - return 0.5 * (right - left) / divisor; -} diff --git a/roborts_tracking/KCFcpp/src/kcftracker.hpp b/roborts_tracking/KCFcpp/src/kcftracker.hpp deleted file mode 100644 index 4463f4a9..00000000 --- a/roborts_tracking/KCFcpp/src/kcftracker.hpp +++ /dev/null @@ -1,151 +0,0 @@ -/* - -Tracker based on Kernelized Correlation Filter (KCF) [1] and Circulant Structure with Kernels (CSK) [2]. -CSK is implemented by using raw gray level features, since it is a single-channel filter. -KCF is implemented by using HOG features (the default), since it extends CSK to multiple channels. - -[1] J. F. Henriques, R. Caseiro, P. Martins, J. Batista, -"High-Speed Tracking with Kernelized Correlation Filters", TPAMI 2015. - -[2] J. F. Henriques, R. Caseiro, P. Martins, J. Batista, -"Exploiting the Circulant Structure of Tracking-by-detection with Kernels", ECCV 2012. - -Authors: Joao Faro, Christian Bailer, Joao F. Henriques -Contacts: joaopfaro@gmail.com, Christian.Bailer@dfki.de, henriques@isr.uc.pt -Institute of Systems and Robotics - University of Coimbra / Department Augmented Vision DFKI - - -Constructor parameters, all boolean: - hog: use HOG features (default), otherwise use raw pixels - fixed_window: fix window size (default), otherwise use ROI size (slower but more accurate) - multiscale: use multi-scale tracking (default; cannot be used with fixed_window = true) - -Default values are set for all properties of the tracker depending on the above choices. -Their values can be customized further before calling init(): - interp_factor: linear interpolation factor for adaptation - sigma: gaussian kernel bandwidth - lambda: regularization - cell_size: HOG cell size - padding: horizontal area surrounding the target, relative to its size - output_sigma_factor: bandwidth of gaussian target - template_size: template size in pixels, 0 to use ROI size - scale_step: scale step for multi-scale estimation, 1 to disable it - scale_weight: to downweight detection scores of other scales for added stability - -For speed, the value (template_size/cell_size) should be a power of 2 or a product of small prime numbers. - -Inputs to init(): - image is the initial frame. - roi is a cv::Rect with the target positions in the initial frame - -Inputs to update(): - image is the current frame. - -Outputs of update(): - cv::Rect with target positions for the current frame - - -By downloading, copying, installing or using the software you agree to this license. -If you do not agree to this license, do not download, install, -copy or use the software. - - - License Agreement - For Open Source Computer Vision Library - (3-clause BSD License) - -Redistribution and use in source and binary forms, with or without modification, -are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, - this list of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - * Neither the names of the copyright holders nor the names of the contributors - may be used to endorse or promote products derived from this software - without specific prior written permission. - -This software is provided by the copyright holders and contributors "as is" and -any express or implied warranties, including, but not limited to, the implied -warranties of merchantability and fitness for a particular purpose are disclaimed. -In no event shall copyright holders or contributors be liable for any direct, -indirect, incidental, special, exemplary, or consequential damages -(including, but not limited to, procurement of substitute goods or services; -loss of use, data, or profits; or business interruption) however caused -and on any theory of liability, whether in contract, strict liability, -or tort (including negligence or otherwise) arising in any way out of -the use of this software, even if advised of the possibility of such damage. - */ - -#pragma once - -#include "tracker.h" - -#ifndef _OPENCV_KCFTRACKER_HPP_ -#define _OPENCV_KCFTRACKER_HPP_ -#endif - -class KCFTracker : public Tracker -{ -public: - // Constructor - KCFTracker(bool hog = true, bool fixed_window = true, bool multiscale = true, bool lab = true); - - // Initialize tracker - virtual void init(const cv::Rect &roi, cv::Mat image); - - // Update position based on the new frame - virtual cv::Rect update(cv::Mat image); - - float interp_factor; // linear interpolation factor for adaptation - float sigma; // gaussian kernel bandwidth - float lambda; // regularization - int cell_size; // HOG cell size - int cell_sizeQ; // cell size^2, to avoid repeated operations - float padding; // extra area surrounding the target - float output_sigma_factor; // bandwidth of gaussian target - int template_size; // template size - float scale_step; // scale step for multi-scale estimation - float scale_weight; // to downweight detection scores of other scales for added stability - -protected: - // Detect object in the current frame. - cv::Point2f detect(cv::Mat z, cv::Mat x, float &peak_value); - - // train tracker with a single image - void train(cv::Mat x, float train_interp_factor); - - // Evaluates a Gaussian kernel with bandwidth SIGMA for all relative shifts between input images X and Y, which must both be MxN. They must also be periodic (ie., pre-processed with a cosine window). - cv::Mat gaussianCorrelation(cv::Mat x1, cv::Mat x2); - - // Create Gaussian Peak. Function called only in the first frame. - cv::Mat createGaussianPeak(int sizey, int sizex); - - // Obtain sub-window from image, with replication-padding and extract features - cv::Mat getFeatures(const cv::Mat & image, bool inithann, float scale_adjust = 1.0f); - - // Initialize Hanning window. Function called only in the first frame. - void createHanningMats(); - - // Calculate sub-pixel peak for one dimension - float subPixelPeak(float left, float center, float right); - - cv::Mat _alphaf; - cv::Mat _prob; - cv::Mat _tmpl; - cv::Mat _num; - cv::Mat _den; - cv::Mat _labCentroids; - -private: - int size_patch[3]; - cv::Mat hann; - cv::Size _tmpl_sz; - float _scale; - int _gaussian_size; - bool _hogfeatures; - bool _labfeatures; -}; diff --git a/roborts_tracking/KCFcpp/src/labdata.hpp b/roborts_tracking/KCFcpp/src/labdata.hpp deleted file mode 100644 index 26e7a65f..00000000 --- a/roborts_tracking/KCFcpp/src/labdata.hpp +++ /dev/null @@ -1,17 +0,0 @@ -const int nClusters = 15; -float data[nClusters][3] = { -{161.317504, 127.223401, 128.609333}, -{142.922425, 128.666965, 127.532319}, -{67.879757, 127.721830, 135.903311}, -{92.705062, 129.965717, 137.399500}, -{120.172257, 128.279647, 127.036493}, -{195.470568, 127.857070, 129.345415}, -{41.257102, 130.059468, 132.675336}, -{12.014861, 129.480555, 127.064714}, -{226.567086, 127.567831, 136.345727}, -{154.664210, 131.676606, 156.481669}, -{121.180447, 137.020793, 153.433743}, -{87.042204, 137.211742, 98.614874}, -{113.809537, 106.577104, 157.818094}, -{81.083293, 170.051905, 148.904079}, -{45.015485, 138.543124, 102.402528}}; \ No newline at end of file diff --git a/roborts_tracking/KCFcpp/src/recttools.hpp b/roborts_tracking/KCFcpp/src/recttools.hpp deleted file mode 100644 index 780ad328..00000000 --- a/roborts_tracking/KCFcpp/src/recttools.hpp +++ /dev/null @@ -1,140 +0,0 @@ -/* -Author: Christian Bailer -Contact address: Christian.Bailer@dfki.de -Department Augmented Vision DFKI - - License Agreement - For Open Source Computer Vision Library - (3-clause BSD License) - -Redistribution and use in source and binary forms, with or without modification, -are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, - this list of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - * Neither the names of the copyright holders nor the names of the contributors - may be used to endorse or promote products derived from this software - without specific prior written permission. - -This software is provided by the copyright holders and contributors "as is" and -any express or implied warranties, including, but not limited to, the implied -warranties of merchantability and fitness for a particular purpose are disclaimed. -In no event shall copyright holders or contributors be liable for any direct, -indirect, incidental, special, exemplary, or consequential damages -(including, but not limited to, procurement of substitute goods or services; -loss of use, data, or profits; or business interruption) however caused -and on any theory of liability, whether in contract, strict liability, -or tort (including negligence or otherwise) arising in any way out of -the use of this software, even if advised of the possibility of such damage. -*/ - -#pragma once - -//#include -#include - -#ifndef _OPENCV_RECTTOOLS_HPP_ -#define _OPENCV_RECTTOOLS_HPP_ -#endif - -namespace RectTools -{ - -template -inline cv::Vec center(const cv::Rect_ &rect) -{ - return cv::Vec (rect.x + rect.width / (t) 2, rect.y + rect.height / (t) 2); -} - -template -inline t x2(const cv::Rect_ &rect) -{ - return rect.x + rect.width; -} - -template -inline t y2(const cv::Rect_ &rect) -{ - return rect.y + rect.height; -} - -template -inline void resize(cv::Rect_ &rect, float scalex, float scaley = 0) -{ - if (!scaley)scaley = scalex; - rect.x -= rect.width * (scalex - 1.f) / 2.f; - rect.width *= scalex; - - rect.y -= rect.height * (scaley - 1.f) / 2.f; - rect.height *= scaley; - -} - -template -inline void limit(cv::Rect_ &rect, cv::Rect_ limit) -{ - if (rect.x + rect.width > limit.x + limit.width)rect.width = (limit.x + limit.width - rect.x); - if (rect.y + rect.height > limit.y + limit.height)rect.height = (limit.y + limit.height - rect.y); - if (rect.x < limit.x) - { - rect.width -= (limit.x - rect.x); - rect.x = limit.x; - } - if (rect.y < limit.y) - { - rect.height -= (limit.y - rect.y); - rect.y = limit.y; - } - if(rect.width<0)rect.width=0; - if(rect.height<0)rect.height=0; -} - -template -inline void limit(cv::Rect_ &rect, t width, t height, t x = 0, t y = 0) -{ - limit(rect, cv::Rect_ (x, y, width, height)); -} - -template -inline cv::Rect getBorder(const cv::Rect_ &original, cv::Rect_ & limited) -{ - cv::Rect_ res; - res.x = limited.x - original.x; - res.y = limited.y - original.y; - res.width = x2(original) - x2(limited); - res.height = y2(original) - y2(limited); - assert(res.x >= 0 && res.y >= 0 && res.width >= 0 && res.height >= 0); - return res; -} - -inline cv::Mat subwindow(const cv::Mat &in, const cv::Rect & window, int borderType = cv::BORDER_CONSTANT) -{ - cv::Rect cutWindow = window; - RectTools::limit(cutWindow, in.cols, in.rows); - if (cutWindow.height <= 0 || cutWindow.width <= 0)assert(0); //return cv::Mat(window.height,window.width,in.type(),0) ; - cv::Rect border = RectTools::getBorder(window, cutWindow); - cv::Mat res = in(cutWindow); - - if (border != cv::Rect(0, 0, 0, 0)) - { - cv::copyMakeBorder(res, res, border.y, border.height, border.x, border.width, borderType); - } - return res; -} - -inline cv::Mat getGrayImage(cv::Mat img) -{ - cv::cvtColor(img, img, CV_BGR2GRAY); - img.convertTo(img, CV_32F, 1 / 255.f); - return img; -} - -} - - - diff --git a/roborts_tracking/KCFcpp/src/runtracker.cpp b/roborts_tracking/KCFcpp/src/runtracker.cpp deleted file mode 100644 index e44c9260..00000000 --- a/roborts_tracking/KCFcpp/src/runtracker.cpp +++ /dev/null @@ -1,139 +0,0 @@ -#include -#include -#include -#include - -#include -#include - -#include "kcftracker.hpp" - -#include - -using namespace std; -using namespace cv; - -int main(int argc, char* argv[]){ - - if (argc > 5) return -1; - - bool HOG = true; - bool FIXEDWINDOW = false; - bool MULTISCALE = true; - bool SILENT = true; - bool LAB = false; - - for(int i = 0; i < argc; i++){ - if ( strcmp (argv[i], "hog") == 0 ) - HOG = true; - if ( strcmp (argv[i], "fixed_window") == 0 ) - FIXEDWINDOW = true; - if ( strcmp (argv[i], "singlescale") == 0 ) - MULTISCALE = false; - if ( strcmp (argv[i], "show") == 0 ) - SILENT = false; - if ( strcmp (argv[i], "lab") == 0 ){ - LAB = true; - HOG = true; - } - if ( strcmp (argv[i], "gray") == 0 ) - HOG = false; - } - - // Create KCFTracker object - KCFTracker tracker(HOG, FIXEDWINDOW, MULTISCALE, LAB); - - // Frame readed - Mat frame; - - // Tracker results - Rect result; - - // Path to list.txt - ifstream listFile; - string fileName = "images.txt"; - listFile.open(fileName); - - // Read groundtruth for the 1st frame - ifstream groundtruthFile; - string groundtruth = "region.txt"; - groundtruthFile.open(groundtruth); - string firstLine; - getline(groundtruthFile, firstLine); - groundtruthFile.close(); - - istringstream ss(firstLine); - - // Read groundtruth like a dumb - float x1, y1, x2, y2, x3, y3, x4, y4; - char ch; - ss >> x1; - ss >> ch; - ss >> y1; - ss >> ch; - ss >> x2; - ss >> ch; - ss >> y2; - ss >> ch; - ss >> x3; - ss >> ch; - ss >> y3; - ss >> ch; - ss >> x4; - ss >> ch; - ss >> y4; - - // Using min and max of X and Y for groundtruth rectangle - float xMin = min(x1, min(x2, min(x3, x4))); - float yMin = min(y1, min(y2, min(y3, y4))); - float width = max(x1, max(x2, max(x3, x4))) - xMin; - float height = max(y1, max(y2, max(y3, y4))) - yMin; - - - // Read Images - ifstream listFramesFile; - string listFrames = "images.txt"; - listFramesFile.open(listFrames); - string frameName; - - - // Write Results - ofstream resultsFile; - string resultsPath = "output.txt"; - resultsFile.open(resultsPath); - - // Frame counter - int nFrames = 0; - - - while ( getline(listFramesFile, frameName) ){ - frameName = frameName; - - // Read each frame from the list - frame = imread(frameName, CV_LOAD_IMAGE_COLOR); - - // First frame, give the groundtruth to the tracker - if (nFrames == 0) { - tracker.init( Rect(xMin, yMin, width, height), frame ); - rectangle( frame, Point( xMin, yMin ), Point( xMin+width, yMin+height), Scalar( 0, 255, 255 ), 1, 8 ); - resultsFile << xMin << "," << yMin << "," << width << "," << height << endl; - } - // Update - else{ - result = tracker.update(frame); - rectangle( frame, Point( result.x, result.y ), Point( result.x+result.width, result.y+result.height), Scalar( 0, 255, 255 ), 1, 8 ); - resultsFile << result.x << "," << result.y << "," << result.width << "," << result.height << endl; - } - - nFrames++; - - if (!SILENT){ - imshow("Image", frame); - waitKey(1); - } - } - resultsFile.close(); - - listFile.close(); - -} diff --git a/roborts_tracking/KCFcpp/src/tracker.h b/roborts_tracking/KCFcpp/src/tracker.h deleted file mode 100644 index 41b5ea3d..00000000 --- a/roborts_tracking/KCFcpp/src/tracker.h +++ /dev/null @@ -1,39 +0,0 @@ -/* - * File: BasicTracker.h - * Author: Joao F. Henriques, Joao Faro, Christian Bailer - * Contact address: henriques@isr.uc.pt, joaopfaro@gmail.com, Christian.Bailer@dfki.de - * Instute of Systems and Robotics- University of COimbra / Department Augmented Vision DFKI - * - * This source code is provided for for research purposes only. For a commercial license or a different use case please contact us. - * You are not allowed to publish the unmodified sourcecode on your own e.g. on your webpage. Please refer to the official download page instead. - * If you want to publish a modified/extended version e.g. because you wrote a publication with a modified version of the sourcecode you need our - * permission (Please contact us for the permission). - * - * We reserve the right to change the license of this sourcecode anytime to BSD, GPL or LGPL. - * By using the sourcecode you agree to possible restrictions and requirements of these three license models so that the license can be changed - * anytime without you knowledge. - */ - - - -#pragma once - -#include -#include - -class Tracker -{ -public: - Tracker() {} - virtual ~Tracker() { } - - virtual void init(const cv::Rect &roi, cv::Mat image) = 0; - virtual cv::Rect update( cv::Mat image)=0; - - -protected: - cv::Rect_ _roi; -}; - - - diff --git a/roborts_tracking/package.xml b/roborts_tracking/package.xml deleted file mode 100755 index 5826fa37..00000000 --- a/roborts_tracking/package.xml +++ /dev/null @@ -1,24 +0,0 @@ - - roborts_tracking - 1.0.0 - - The roborts_tracking package provides object tracking for RoboMaster AI Robot - - RoboMaster - RoboMaster - GPL 3.0 - https://github.com/RoboMaster/RoboRTS - - catkin - - roscpp - rospy - tf - roborts_msgs - - roscpp - rospy - tf - roborts_msgs - - diff --git a/roborts_tracking/tracking_test.cpp b/roborts_tracking/tracking_test.cpp deleted file mode 100644 index 1aadaad5..00000000 --- a/roborts_tracking/tracking_test.cpp +++ /dev/null @@ -1,196 +0,0 @@ -/**************************************************************************** - * Copyright (C) 2019 RoboMaster. - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of  - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - ***************************************************************************/ - -#include -#include -#include -#include -#include -#include -#include "roborts_msgs/GimbalAngle.h" - -#include "tracking_utility.h" - -#include "opencv2/imgproc/imgproc.hpp" -#include "opencv2/highgui/highgui.hpp" -#include "KCFcpp/src/kcftracker.hpp" - -#define HOG 1 -#define FIXEDWINDOW 1 -#define MULTISCALE 1 -#define LAB 1 - -typedef std::chrono::time_point timer; -typedef std::chrono::duration duration; - -using namespace std; -using namespace cv; - -int main(int argc, char** argv) -{ - ros::init(argc, argv, "roborts_tracking_node"); - ros::NodeHandle nh; - auto pub= nh.advertise("cmd_gimbal_angle", 30); - const char winName[]="My Camera"; - char message1[100]; - char message2[100]; - Rect roi(0,0,0,0); - TrackingUtility tu; - KCFTracker *tracker = NULL; - - cv::namedWindow(winName,1); - cv::setMouseCallback(winName,TrackingUtility::mouseCallback, (void*)&tu); - - - VideoCapture video(0); - int img_width = 640; - int img_height = 480; - video.set(CV_CAP_PROP_FRAME_WIDTH,img_width); - video.set(CV_CAP_PROP_FRAME_HEIGHT,img_height); - img_width = video.get(CV_CAP_PROP_FRAME_WIDTH); - img_height = video.get(CV_CAP_PROP_FRAME_HEIGHT); - - if (!video.isOpened()) { - cout << "cannot read video!" << endl; - return -1; - } - //可选BOOSTING, MIL, KCF, TLD, MEDIANFLOW, or GOTURN - - while(ros::ok()) - { - char c = cv::waitKey(10); - if(c==27) - { - if(tracker != NULL) - { - delete tracker; - tracker = NULL; - } - break; // Quit if ESC is pressed - } - - tu.getKey(c); //Internal states will be updated based on key pressed. - - Mat frame; - if(video.read(frame)){ - int dx = 0; - int dy = 0; - int yawRate = 0; - int pitchRate = 0; - timer trackerStartTime, trackerFinishTime; - duration trackerTimeDiff; - - roborts_msgs::GimbalAngle gimbal_angle; - int k = 1920/img_width; - switch(tu.getState()) - { - case TrackingUtility::STATE_IDLE: - roi = tu.getROI(); - sprintf(message2, "Please select ROI and press g"); - break; - - case TrackingUtility::STATE_INIT: - cout << "g pressed, initialize tracker" << endl; - sprintf(message2, "g pressed, initialize tracker"); - roi = tu.getROI(); - tracker = new KCFTracker(HOG, FIXEDWINDOW, MULTISCALE, LAB); - tracker->init(roi, frame); - tu.startTracker(); - break; - - case TrackingUtility::STATE_ONGOING: - trackerStartTime = std::chrono::high_resolution_clock::now(); - roi = tracker->update(frame); - trackerFinishTime = std::chrono::high_resolution_clock::now(); - trackerTimeDiff = trackerFinishTime - trackerStartTime; - sprintf(message2, "Tracking: bounding box update time = %.2f ms\n", trackerTimeDiff.count()*1000.0); - - // send gimbal speed command - dx = (int)(roi.x + roi.width/2 - img_width/2); - dy = (int)(roi.y + roi.height/2 - img_height/2); - - yawRate = -dx; - pitchRate = dy; - cout<<"yaw_rate:"<500/k) { - yawRate = ((yawRate>0)?1:-1)*500/k; - } - - if(abs(pitchRate) < 10/k) - { - pitchRate = 0; - } - else if(abs(pitchRate)>500/k) { - pitchRate = ((pitchRate>0)?1:-1)*500/k; - } - - gimbal_angle.pitch_mode = true; - gimbal_angle.pitch_angle = pitchRate/180.*M_PI/110.*k; - - gimbal_angle.yaw_mode = true; - gimbal_angle.yaw_angle = yawRate/180.*M_PI/160.*k; - pub.publish(gimbal_angle); - - break; - - case TrackingUtility::STATE_STOP: - cout << "s pressed, stop tracker" << endl; - sprintf(message2, "s pressed, stop tracker"); - delete tracker; - tracker = NULL; - tu.stopTracker(); - roi = tu.getROI(); - break; - - default: - break; - } - dx = roi.x + roi.width/2 - img_width/2; - dy = roi.y + roi.height/2 - img_height/2; - - cv::circle(frame, Point(img_width/2, img_height/2), 5, cv::Scalar(255,0,0), 2, 8); - if(roi.width != 0) - { - cv::circle(frame, Point(roi.x + roi.width/2, roi.y + roi.height/2), 3, cv::Scalar(0,0,255), 1, 8); - - cv::line(frame, Point(img_width/2, img_height/2), - Point(roi.x + roi.width/2, roi.y + roi.height/2), - cv::Scalar(0,255,255)); - } - - cv::rectangle(frame, roi, cv::Scalar(0,255,0), 1, 8, 0 ); - sprintf(message1,"dx=%04d, dy=%04d",dx, dy); - putText(frame, message1, Point2f(20,30), FONT_HERSHEY_SIMPLEX, 0.5, Scalar(0,255,0)); - putText(frame, message2, Point2f(20,60), FONT_HERSHEY_SIMPLEX, 0.5, Scalar(0,255,0)); - cv::imshow(winName, frame); - - } - - } - - if(tracker) - { - delete tracker; - } - - return 0; -} \ No newline at end of file diff --git a/roborts_tracking/tracking_utility.cpp b/roborts_tracking/tracking_utility.cpp deleted file mode 100644 index 6b3ca3f5..00000000 --- a/roborts_tracking/tracking_utility.cpp +++ /dev/null @@ -1,107 +0,0 @@ -/**************************************************************************** - * Copyright (C) 2019 RoboMaster. - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of  - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - ***************************************************************************/ - -#include "tracking_utility.h" -#include -void TrackingUtility::mouseCallback(int event, int x, int y, int f, void *p) -{ - TrackingUtility *u = reinterpret_cast(p); - if(u->state != STATE_IDLE) - { - std::cout << "Currently tracking, press s key to stop" << std::endl; - return; - } - - switch(event) - { - case CV_EVENT_LBUTTONDOWN : - u->mouseClicked = true; - u->roiSelected = false; - u->P1 = cv::Point(x,y); - u->P2 = cv::Point(x,y); - break; - - case CV_EVENT_LBUTTONUP : - u->P2 = cv::Point(x,y); - u->mouseClicked=false; - if(u->P2 != u->P1) - { - u->roiSelected = true; - } - break; - - case CV_EVENT_MOUSEMOVE : - if(u->mouseClicked) - { - u->P2 = cv::Point(x,y); - } - break; - - default : - break; - } - - if(u->mouseClicked) - { - u->roi = cv::Rect(u->P1, u->P2); - printf("Current Region of Interest: %d, %d, %d, %d\n", u->roi.tl().x, u->roi.tl().y, u->roi.br().x, u->roi.br().y); - } -} - -cv::Rect TrackingUtility::getROI() -{ - return roi; -} - -TrackingUtility::TrackingState TrackingUtility::getState() -{ - return state; -} - -void TrackingUtility::startTracker() -{ - state = STATE_ONGOING; -} - -void TrackingUtility::stopTracker() -{ - state = STATE_IDLE; -} - -void TrackingUtility::getKey(char c) -{ - switch(c) - { - case 'g': - if( (state == STATE_IDLE) && (roiSelected == true)) - { - state = STATE_INIT; - } - break; - - case 's': - if( state == STATE_ONGOING ) - { - state = STATE_STOP; - roi = cv::Rect(0,0,0,0); //when we press s, should clear bounding box - } - break; - - default: - break; - } -} \ No newline at end of file diff --git a/roborts_tracking/tracking_utility.h b/roborts_tracking/tracking_utility.h deleted file mode 100644 index 4ba88eb4..00000000 --- a/roborts_tracking/tracking_utility.h +++ /dev/null @@ -1,66 +0,0 @@ -/**************************************************************************** - * Copyright (C) 2019 RoboMaster. - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of  - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - ***************************************************************************/ - -#ifndef TEST_TRACKING_UTILITY_H -#define TEST_TRACKING_UTILITY_H -#include "opencv2/opencv.hpp" -/*! @brief - * The TrackingUtility Class handles simple start and stop tracking logic - */ -class TrackingUtility -{ -public: - TrackingUtility() - : P1(0,0), - P2(0,0), - roi(0,0,0,0), - mouseClicked(false), - roiSelected(false), - state(STATE_IDLE) - { - } - - typedef enum TrackingState - { - STATE_IDLE, - STATE_INIT, - STATE_ONGOING, - STATE_STOP - } TrackingState; - - static void mouseCallback(int event, int x, int y, int f, void *p); - - cv::Point P1; - cv::Point P2; - bool mouseClicked; - cv::Rect roi; - - /*! - * start_tracking is set true when you select a region and press 'g' - * is set to false when you press 's' - */ - bool roiSelected; - TrackingState state; - TrackingState getState(); - - void startTracker(); - void stopTracker(); - - cv::Rect getROI(); - void getKey(char c); -}; -#endif //TEST_TRACKING_UTILITY_H