camera.cpp
Go to the documentation of this file.
2 
4 
5  pCam_ = nullptr;
6  timestamp_ = 0;
7 
8 }
9 
10 acquisition::Camera::Camera(CameraPtr pCam) {
11 
12  pCam_ = pCam;
13 
14  if (pCam_->IsInitialized()) {
15  ROS_WARN_STREAM("Camera already initialized. Deinitializing...");
16  pCam_->EndAcquisition();
17  pCam_->DeInit();
18  }
19 
20  lastFrameID_ = -1;
21  frameID_ = -1;
22  MASTER_ = false;
23  timestamp_ = 0;
24  GET_NEXT_IMAGE_TIMEOUT_ = EVENT_TIMEOUT_INFINITE;
25 }
26 
28 
29  pCam_->Init();
30 
31 }
32 
34 
35  pCam_->DeInit();
36 
37 }
38 
40  ImagePtr pResultImage;
41  try{
42  pResultImage = pCam_->GetNextImage(GET_NEXT_IMAGE_TIMEOUT_);
43  // Check if the Image is complete
44 
45  if (pResultImage->IsIncomplete()) {
46 
47  ROS_WARN_STREAM("Image incomplete with image status " << pResultImage->GetImageStatus() << "!");
48 
49  } else {
50 
51  timestamp_ = pResultImage->GetTimeStamp();
52 
53  if (frameID_ >= 0) {
55  frameID_ = pResultImage->GetFrameID();
56  ROS_WARN_STREAM_COND(frameID_ > lastFrameID_ + 1,"Frames are being skipped!");
57  } else {
58  frameID_ = pResultImage->GetFrameID();
59  ROS_ASSERT_MSG(frameID_ == 0 ,"First frame ID was not zero! Might cause sync issues later...");
60  }
61 
62  }
63 
64  ROS_DEBUG_STREAM("Grabbed frame from camera " << get_id() << " with timestamp " << timestamp_*1000);
65  return pResultImage;
66  }
67  catch(Spinnaker::Exception &e){
68  ROS_FATAL_STREAM(e.what()<<"\n Likely reason is that slaves are not triggered. Check GPIO cables\n");
69  }
70 
71  return pResultImage;
72 }
73 
74 // Returns last timestamp
76 
77  stringstream ss;
78  ss<<timestamp_*1000;
79  return ss.str();
80 
81 }
82 
84 
85  return frameID_;
86 
87 }
88 
90 
91  try{
92  ImagePtr pResultImage = grab_frame();
93  return convert_to_mat(pResultImage);
94  }
95  catch(Spinnaker::Exception &e){
96  ros::shutdown();
97  }
98 
99 
100 }
101 
103 
104  ImagePtr convertedImage;
105  if (COLOR_)
106  convertedImage = pImage->Convert(PixelFormat_BGR8); //, NEAREST_NEIGHBOR);
107  else
108  convertedImage = pImage->Convert(PixelFormat_Mono8); //, NEAREST_NEIGHBOR);
109  unsigned int XPadding = convertedImage->GetXPadding();
110  unsigned int YPadding = convertedImage->GetYPadding();
111  unsigned int rowsize = convertedImage->GetWidth();
112  unsigned int colsize = convertedImage->GetHeight();
113  //image data contains padding. When allocating Mat container size, you need to account for the X,Y image data padding.
114  Mat img;
115  if (COLOR_)
116  img = Mat(colsize + YPadding, rowsize + XPadding, CV_8UC3, convertedImage->GetData(), convertedImage->GetStride());
117  else
118  img = Mat(colsize + YPadding, rowsize + XPadding, CV_8UC1, convertedImage->GetData(), convertedImage->GetStride());
119  return img.clone();
120  // return img;
121 
122 }
123 
125 
126  ROS_DEBUG_STREAM("Begin Acquisition...");
127  pCam_->BeginAcquisition();
128 
129 }
130 
132 
133  if (pCam_->GetNumImagesInUse())
134  ROS_WARN_STREAM("Some images still currently in use! Use image->Release() before deinitializing.");
135 
136  ROS_DEBUG_STREAM("End Acquisition...");
137  pCam_->EndAcquisition();
138 
139 }
140 
141 void acquisition::Camera::setEnumValue(string setting, string value) {
142 
143  INodeMap & nodeMap = pCam_->GetNodeMap();
144 
145  // Retrieve enumeration node from nodemap
146  CEnumerationPtr ptr = nodeMap.GetNode(setting.c_str());
147  if (!IsAvailable(ptr) || !IsWritable(ptr))
148  ROS_FATAL_STREAM("Unable to set " << setting << " to " << value << " (enum retrieval). Aborting...");
149 
150  // Retrieve entry node from enumeration node
151  CEnumEntryPtr ptrValue = ptr->GetEntryByName(value.c_str());
152  if (!IsAvailable(ptrValue) || !IsReadable(ptrValue))
153  ROS_FATAL_STREAM("Unable to set " << setting << " to " << value << " (entry retrieval). Aborting...");
154 
155  // retrieve value from entry node
156  int64_t valueToSet = ptrValue->GetValue();
157 
158  // Set value from entry node as new value of enumeration node
159  ptr->SetIntValue(valueToSet);
160 
161  ROS_DEBUG_STREAM(setting << " set to " << value);
162 
163 }
164 
165 void acquisition::Camera::setIntValue(string setting, int val) {
166 
167  INodeMap & nodeMap = pCam_->GetNodeMap();
168 
169  CIntegerPtr ptr = nodeMap.GetNode(setting.c_str());
170  if (!IsAvailable(ptr) || !IsWritable(ptr)) {
171  ROS_FATAL_STREAM("Unable to set " << setting << " to " << val << " (ptr retrieval). Aborting...");
172  }
173  ptr->SetValue(val);
174 
175  ROS_DEBUG_STREAM(setting << " set to " << val);
176 
177 }
178 
179 void acquisition::Camera::setFloatValue(string setting, float val) {
180 
181  INodeMap & nodeMap = pCam_->GetNodeMap();
182 
183  CFloatPtr ptr = nodeMap.GetNode(setting.c_str());
184  if (!IsAvailable(ptr) || !IsWritable(ptr)) {
185  ROS_FATAL_STREAM("Unable to set " << setting << " to " << val << " (ptr retrieval). Aborting...");
186  }
187  ptr->SetValue(val);
188 
189  ROS_DEBUG_STREAM(setting << " set to " << val);
190 
191 }
192 
193 void acquisition::Camera::setBoolValue(string setting, bool val) {
194 
195  INodeMap & nodeMap = pCam_->GetNodeMap();
196 
197  CBooleanPtr ptr = nodeMap.GetNode(setting.c_str());
198  if (!IsAvailable(ptr) || !IsWritable(ptr)) {
199  ROS_FATAL_STREAM("Unable to set " << setting << " to " << val << " (ptr retrieval). Aborting...");
200  }
201  ptr->SetValue(val);
202 
203  ROS_DEBUG_STREAM(setting << " set to " << val);
204 
205 }
206 
207 
208 
209 void acquisition::Camera::setResolutionPixels(int width, int height) {
210  CIntegerPtr ptrHeight=pCam_->GetNodeMap().GetNode("Height");
211  CIntegerPtr ptrWidth=pCam_->GetNodeMap().GetNode("Width");
212  if (!IsAvailable(ptrWidth) || !IsWritable(ptrWidth)){
213  ROS_FATAL_STREAM("Unable to set width" << "). Aborting...");
214  return ;
215  }
216  int64_t widthMax = ptrWidth->GetMax();
217  if(widthMax<width)
218  width=widthMax;
219  ptrWidth->SetValue(width);
220  ROS_DEBUG_STREAM("Set Width"<<width);
221 
222  if (!IsAvailable(ptrHeight) || !IsWritable(ptrHeight)){
223  ROS_FATAL_STREAM("Unable to set height" << "). Aborting...");
224  return ;
225  }
226  int64_t heightMax = ptrHeight->GetMax();
227  if(heightMax<height)
228  height=heightMax;
229 
230  ROS_DEBUG_STREAM("Set Height"<<height);
231  ptrHeight->SetValue(height);
232 }
233 
234 void acquisition::Camera::adcBitDepth(gcstring bitDep) {
235  CEnumerationPtr ptrADC = pCam_->GetNodeMap().GetNode("AdcBitDepth");
236  if (!IsAvailable(ptrADC) || !IsWritable(ptrADC)){
237  ROS_FATAL_STREAM("Unable to set ADC Bit " << "). Aborting...");
238  return ;
239  }
240 
241  CEnumEntryPtr ptrADCA = ptrADC->GetEntryByName(bitDep);
242  int currDepth=ptrADCA->GetValue();
243  ptrADC->SetIntValue(currDepth);
244  ROS_DEBUG_STREAM("BPS: "<<ptrADC->GetIntValue());
245 
246 }
247 
249  INodeMap & sNodeMap = pCam_->GetTLStreamNodeMap();
250  CIntegerPtr StreamNode = sNodeMap.GetNode("StreamDefaultBufferCount");
251  int64_t bufferCount = StreamNode->GetValue();
252  if (!IsAvailable(StreamNode) || !IsWritable(StreamNode)){
253  ROS_FATAL_STREAM("Unable to set StreamMode " << "). Aborting...");
254  return;
255  }
256  StreamNode->SetValue(numBuf);
257  ROS_DEBUG_STREAM("Set Buf "<<numBuf<<endl);
258 }
259 
261  CBooleanPtr ptrISPEn=pCam_->GetNodeMap().GetNode("IspEnable");
262  if (!IsAvailable(ptrISPEn) || !IsWritable(ptrISPEn)){
263  ROS_FATAL_STREAM("Unable to set ISP Enable (node retrieval; camera " << "). Aborting...");
264  return;
265  }
266  ptrISPEn->SetValue("True");
267 }
268 
270  CBooleanPtr ptrAcquisitionFrameRateEnable=pCam_->GetNodeMap().GetNode("AcquisitionFrameRateEnable");
271  if (!IsAvailable(ptrAcquisitionFrameRateEnable) || !IsWritable(ptrAcquisitionFrameRateEnable)){
272  ROS_FATAL_STREAM("Unable to set frameRateEnable (node retrieval; camera " << "). Aborting...");
273  return;
274  }
275 
276  ptrAcquisitionFrameRateEnable->SetValue("True");
277 }
278 
279 void acquisition::Camera::setPixelFormat(gcstring formatPic) {
280  CEnumerationPtr ptrPixelFormat = pCam_->GetNodeMap().GetNode(formatPic);
281  if ( !IsWritable(ptrPixelFormat)){
282  ROS_FATAL_STREAM("Unable to set Pixel Format " << "). Aborting...");
283  return ;
284  }
285  CEnumEntryPtr ptrPixelEnt = ptrPixelFormat->GetEntryByName("RGB8Packed");
286  if (!IsAvailable(ptrPixelEnt) || !IsReadable(ptrPixelEnt)){
287  ROS_FATAL_STREAM("Unable to set RGBPoint" << "). Aborting...");
288  return ;
289  }
290  int64_t colorNum = ptrPixelEnt->GetValue();
291 
292  ptrPixelFormat->SetIntValue(colorNum);
293  ROS_DEBUG_STREAM( "Camera " << " set pixel format");
294 }
295 
297 
298  INodeMap & nodeMap = pCam_->GetNodeMap();
299 
300  CCommandPtr ptr = nodeMap.GetNode("TriggerSoftware");
301  if (!IsAvailable(ptr) || !IsWritable(ptr))
302  ROS_FATAL_STREAM("Unable to execute trigger. Aborting...");
303 
304  ROS_DEBUG_STREAM("Executing software trigger...");
305  ptr->Execute();
306 
307 }
308 
309 double acquisition::Camera::getFloatValueMax(string node_string) {
310  INodeMap& nodeMap = pCam_->GetNodeMap();
311 
312  CFloatPtr ptrNodeValue = nodeMap.GetNode(node_string.c_str());
313 
314  if (IsAvailable(ptrNodeValue)){
315  //cout << "\tMax " << ptrNodeValue->GetValue() << "..." << endl;
316  return ptrNodeValue->GetMax();
317  } else {
318  ROS_FATAL_STREAM("Node " << node_string << " not available" << endl);
319  return -1;
320  }
321 }
322 
323 
324 string acquisition::Camera::getTLNodeStringValue(string node_string) {
325  INodeMap& nodeMap = pCam_->GetTLDeviceNodeMap();
326  CStringPtr ptrNodeValue = nodeMap.GetNode(node_string.c_str());
327  if (IsReadable(ptrNodeValue)){
328  return string(ptrNodeValue->GetValue());
329  } else{
330  ROS_FATAL_STREAM("Node " << node_string << " not readable" << endl);
331  return "";
332  }
333 }
334 
336  return getTLNodeStringValue("DeviceSerialNumber");
337 }
338 
340  CFloatPtr ptrExpTest =pCam_->GetNodeMap().GetNode("AutoExposureTargetGreyValue");
341  //CFloatPtr ptrExpTest=pCam_->GetNodeMap().GetNode("ExposureTime");
342  if (!IsAvailable(ptrExpTest) || !IsReadable(ptrExpTest)){
343  ROS_FATAL_STREAM("Unable to set exposure " << "). Aborting..." << endl << endl);
344  return ;
345  }
346  ptrExpTest->SetValue(90.0);
347  ROS_INFO_STREAM("target grey mode Time: "<<ptrExpTest->GetValue()<<endl);
348 
349 }
350 
352  CFloatPtr ptrExpTest=pCam_->GetNodeMap().GetNode("ExposureTime");
353  if (!IsAvailable(ptrExpTest) || !IsReadable(ptrExpTest)){
354  ROS_FATAL_STREAM("Unable to set exposure " << "). Aborting..." << endl << endl);
355  return ;
356  }
357  float expTime=ptrExpTest->GetValue();
358  ROS_DEBUG_STREAM("Exposure Time: "<<expTime<<endl);
359 
360 }
361 bool acquisition::Camera::verifyBinning(int binningDesired) {
362  int actualBinningX = (pCam_ ->SensorWidth())/(pCam_ ->Width());
363  int actualBinningY = (pCam_ ->SensorHeight())/(pCam_ ->Height());
364  if (binningDesired == actualBinningX) return true;
365  else return false;
366 }
367 
368 void acquisition::Camera::calibrationParamsTest(int calibrationWidth, int calibrationHeight) {
369  if ( (pCam_ ->SensorWidth()) != calibrationWidth )
370  ROS_WARN_STREAM(" Looks like your calibration is not done at full Sensor Resolution for cam_id = "<<get_id()<<" , Sensor_Width = "<<(pCam_ ->SensorWidth()) <<" given cameraInfo params:width = "<<calibrationWidth);
371  if ( (pCam_ ->SensorHeight()) != calibrationHeight )
372  ROS_WARN_STREAM(" Looks like your calibration is not done at full Sensor Resolution for cam_id = "<<get_id()<<" , Sensor_Height= "<<(pCam_ ->SensorHeight()) <<" given cameraInfo params:height = "<<calibrationHeight);
373 }
void adcBitDepth(gcstring bitDep)
Definition: camera.cpp:234
bool verifyBinning(int binningDesired)
Definition: camera.cpp:361
ImagePtr grab_frame()
Definition: camera.cpp:39
int64_t timestamp_
Definition: camera.h:77
CameraPtr pCam_
Definition: camera.h:76
void end_acquisition()
Definition: camera.cpp:131
void setFloatValue(string, float)
Definition: camera.cpp:179
Mat grab_mat_frame()
Definition: camera.cpp:89
uint64_t GET_NEXT_IMAGE_TIMEOUT_
Definition: camera.h:83
void setResolutionPixels(int width, int height)
Definition: camera.cpp:209
void setBufferSize(int numBuf)
Definition: camera.cpp:248
double getFloatValueMax(string node_string)
Definition: camera.cpp:309
void begin_acquisition()
Definition: camera.cpp:124
#define ROS_FATAL_STREAM(args)
#define ROS_ASSERT_MSG(cond,...)
void setBoolValue(string, bool)
Definition: camera.cpp:193
#define ROS_WARN_STREAM_COND(cond, args)
void setEnumValue(string, string)
Definition: camera.cpp:141
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
void calibrationParamsTest(int calibrationWidth, int calibrationHeight)
Definition: camera.cpp:368
string get_time_stamp()
Definition: camera.cpp:75
Camera(CameraPtr)
Definition: camera.cpp:10
void setPixelFormat(gcstring formatPic)
Definition: camera.cpp:279
#define ROS_INFO_STREAM(args)
string getTLNodeStringValue(string node_string)
Definition: camera.cpp:324
void targetGreyValueTest()
Definition: camera.cpp:339
void setIntValue(string, int)
Definition: camera.cpp:165
ROSCPP_DECL void shutdown()
Mat convert_to_mat(ImagePtr)
Definition: camera.cpp:102


spinnaker_sdk_camera_driver
Author(s): Abhishek Bajpayee, Pushyami Kaveti, Vikrant Shah
autogenerated on Sun Feb 14 2021 03:34:42