Go to the documentation of this file.00001
00022 #include <iostream>
00023 #include <cstdlib>
00024 #include <cstring>
00025 #include <boost/thread.hpp>
00026
00027 #include <vrmusbcam2.h>
00028 #include "../VrMagicHandler_camhost/VrMagicHandler_camhost.h"
00029
00030 #define PORT 1234
00031 #define MOD_VAL 2
00032 #define EXPOSURE_TIME 5.f
00033
00034
00035 int main(int argc, char *argv[])
00036 {
00037
00038
00039 atexit(VRmUsbCamCleanup);
00040
00041
00042
00043
00044
00045 VRmUsbCamUpdateDeviceKeyList();
00046 VRmDWORD size = 0;
00047 VRmUsbCamGetDeviceKeyListSize(&size);
00048
00049 std::cout << "Found "<< size << " devices" << std::endl;
00050
00051 if(size != 1)
00052 {
00053 std::cout << "found more or none devie..." << std::endl;
00054 std::cout << "this programm ist just for hanlde with one device please change code..." << std::endl;
00055 std::cout << "will exit now...." << std::endl;
00056 exit(EXIT_FAILURE);
00057 }
00058
00059 VRmUsbCamDevice device=0;
00060 VRmDeviceKey* p_device_key=0;
00061
00062 VRmUsbCamGetDeviceKeyListEntry(0, &p_device_key);
00063 if(!p_device_key->m_busy)
00064 {
00065 VRmUsbCamOpenDevice(p_device_key, &device);
00066 }
00067
00068
00069 if(!device)
00070 {
00071 std::cerr << "No suitable VRmagic device found!" << std::endl;
00072 exit(EXIT_FAILURE);
00073 }
00074
00075 std::cout << "Open deivce succesful" << std::endl;
00076
00077
00078
00079
00080
00081 VRmImageFormat target_format;
00082 VRmDWORD port = 0;
00083
00084 VRmBOOL supported;
00085
00086 VRmDWORD num_sensorports=0;
00087 VRmUsbCamGetSensorPortListSize(device, &num_sensorports);
00088
00089
00090 for(VRmDWORD ii=0; ii<num_sensorports;ii++)
00091 {
00092 VRmUsbCamGetSensorPortListEntry(device, ii, &port);
00093 std::cout << "found PORT: " << port << std::endl;
00094
00095
00096 VRmPropId sensor_enable = (VRmPropId)(VRM_PROPID_GRAB_SENSOR_ENABLE_1_B-1+port);
00097 VRmUsbCamGetPropertySupported(device, sensor_enable, &supported);
00098 if(supported)
00099 {
00100
00101 VRmBOOL enable = 1;
00102 if(ii)
00103 enable = 0;
00104 VRmUsbCamSetPropertyValueB(device, sensor_enable, &enable);
00105 }
00106 }
00107
00108
00109 VRmUsbCamGetSensorPortListEntry(device, 0, &port);
00110 std::cout << "PORT: " << port << " is used" << std::endl;
00111
00112
00113 VRmUsbCamGetPropertySupported(device, VRM_PROPID_CAM_EXPOSURE_TIME_F, &supported);
00114 float value=0.f;
00115 VRmUsbCamGetPropertyValueF(device, VRM_PROPID_CAM_EXPOSURE_TIME_F, &value);
00116 std::cout << "ExposureTime: " << value << "ms, changeable: "<< (supported ? "true" : "false") << std::endl;
00117 if(supported)
00118 {
00119 value=EXPOSURE_TIME;
00120
00121
00122 VRmUsbCamSetPropertyValueF(device, VRM_PROPID_CAM_EXPOSURE_TIME_F, &value);
00123 std::cout << "ExposureTime changed to : " << value << "ms" << std::endl;
00124 }
00125
00126
00127 VRmDWORD number_of_target_formats, i;
00128 VRmUsbCamGetTargetFormatListSizeEx2( device, port, &number_of_target_formats );
00129 for ( i = 0; i < number_of_target_formats; ++i )
00130 {
00131 VRmUsbCamGetTargetFormatListEntryEx2(device, port, i, &target_format);
00132 if(target_format.m_color_format == VRM_BGR_3X8)
00133 {
00134 std::cout << "BGR8 found !" << std::endl;
00135 break;
00136 }
00137 }
00138
00139
00140 VRmUsbCamResetFrameCounter(device);
00141 VRmUsbCamStart(device);
00142
00143 VRmImage* p_target_img = 0;
00144 VRmUsbCamNewImage(&p_target_img,target_format);
00145
00146 std::cout << "target img data: "
00147 << "color_format " << p_target_img->m_image_format.m_color_format
00148 << " width " << p_target_img->m_image_format.m_width
00149 << " heigt " << p_target_img->m_image_format.m_height
00150 << " modifier " << p_target_img->m_image_format.m_image_modifier << std::endl;
00151
00152
00153 std::cout << "target img pitch: " << p_target_img->m_pitch << std::endl;
00154
00155
00156 ohm::VrMagicHandler_camhost _rosBrige(PORT);
00157 ohm::ImageType _rosImage;
00158
00159 std::cout << "------------------------------------------------------------" << std::endl;
00160 std::cout << "--- Waiting for ROS-HOST... --------------------------------" << std::endl;
00161 std::cout << "------------------------------------------------------------" << std::endl;
00162 _rosBrige.connect();
00163 std::cout << "Connected to ROS-HOST" << std::endl;
00164
00165
00166
00167 _rosImage.id = port;
00168 _rosImage.dataSize = p_target_img->m_image_format.m_width * 3 * p_target_img->m_image_format.m_height;
00169 _rosImage.dataType = ohm::IMAGE;
00170 _rosImage.compressionType = ohm::NONE;
00171 _rosImage.width = p_target_img->m_image_format.m_width;
00172 _rosImage.height = p_target_img->m_image_format.m_height;
00173 _rosImage.channels = 3;
00174 _rosImage.bytePerPixel = 3;
00175 _rosImage.data = NULL;
00176
00177 OHM_DATA_TYPE* _rosImgBuffer;
00178 _rosImgBuffer = new OHM_DATA_TYPE[_rosImage.dataSize];
00179
00180
00181 bool err_loop = false;
00182 unsigned int cnt = 0;
00183
00184 VRmImage* p_source_img = 0;
00185
00186
00187 while(!err_loop)
00188 {
00189 VRmDWORD frames_dropped;
00190 if(!VRmUsbCamLockNextImageEx(device,port,&p_source_img,&frames_dropped))
00191 {
00192 std::cerr << "Error at locking next image" << std::endl;
00193 err_loop = true;
00194 break;
00195 }
00196
00197
00198 if(cnt % MOD_VAL == 0)
00199 {
00200 if(!VRmUsbCamConvertImage(p_source_img,p_target_img))
00201 {
00202 std::cerr << "Error at converting image: " << VRmUsbCamGetLastError() << std::endl;
00203 err_loop = true;
00204 break;
00205 }
00206
00207
00208
00209
00210
00211
00212
00213
00214 for(unsigned int y = 0; y < _rosImage.height; y++)
00215 {
00216 for(unsigned int x = 0; x < _rosImage.width * 3; x++)
00217 {
00218 _rosImgBuffer[y*_rosImage.width*3 + x] = p_target_img->mp_buffer[y*p_target_img->m_pitch + x];
00219 }
00220 }
00221 _rosImage.data = _rosImgBuffer;
00222 _rosBrige.writeImage(_rosImage);
00223
00224
00225 }
00226 if(!VRmUsbCamUnlockNextImage(device,&p_source_img))
00227 {
00228 std::cerr << "Error at unlocking next image" << std::endl;
00229 err_loop = true;
00230 break;
00231 }
00232
00233
00234 if(frames_dropped)
00235 {
00236 std::cout << frames_dropped <<" frame(s) dropped" << std::endl;
00237 }
00238 cnt++;
00239 }
00240
00241 if(err_loop)
00242 {
00243 std::cerr << "exit with error" << std::endl;
00244 }
00245
00246 VRmUsbCamFreeImage(&p_target_img);
00247
00248 VRmUsbCamStop(device);
00249
00250 VRmUsbCamCloseDevice(device);
00251 return 0;
00252 }