mono_camera.cpp
Go to the documentation of this file.
2 
4 
6 {
7  cameraInfo = ensenso::std::make_shared<sensor_msgs::msg::CameraInfo>();
8  rectifiedCameraInfo = ensenso::std::make_shared<sensor_msgs::msg::CameraInfo>();
9 
10  requestDataServer = MAKE_MONO_SERVER(MonoCamera, RequestData, "request_data");
11  locatePatternServer = MAKE_MONO_SERVER(MonoCamera, LocatePattern, "locate_pattern");
12 }
13 
15 {
18 }
19 
21 {
23  startServers();
26 }
27 
29 {
31  requestDataServer->start();
32  locatePatternServer->start();
33 }
34 
36 {
37  ENSENSO_DEBUG(nh, "Capturing an image...");
38 
39  NxLibCommand capture(cmdCapture, params.serial);
40  capture.parameters()[itmCameras] = params.serial;
41  if (params.captureTimeout > 0)
42  {
43  capture.parameters()[itmTimeout] = params.captureTimeout;
44  }
45  capture.execute();
46 
47  NxLibItem imageNode = cameraNode[itmImages][itmRaw];
48  if (imageNode.isArray())
49  {
50  imageNode = imageNode[0];
51  }
52 
53  if (params.isFileCamera)
54  {
55  // This workaround is needed, because the timestamp of captures from file cameras will not change over time. When
56  // looking up the current tf tree, this will result in errors, because the time of the original timestamp is
57  // requested, which lies in the past (and most often longer than the tfBuffer will store the transform!)
58  return ensenso::ros::now(nh);
59  }
60 
61  return timestampFromNxLibNode(imageNode);
62 }
63 
65 {
68 }
69 
70 void MonoCamera::fillCameraInfoFromNxLib(sensor_msgs::msg::CameraInfoPtr const& info, bool rectified)
71 {
73 
74  NxLibItem calibrationNode = cameraNode[itmCalibration];
75 
76  if (rectified)
77  {
78  GET_D_MATRIX(info).resize(5, 0.);
79  }
80  else
81  {
82  fillDistortionParamsFromNxLib(calibrationNode[itmDistortion], info);
83  }
84 
85  for (int row = 0; row < 3; row++)
86  {
87  for (int column = 0; column < 3; column++)
88  {
89  GET_K_MATRIX(info)[3 * row + column] = calibrationNode[itmCamera][column][row].asDouble();
90  GET_P_MATRIX(info)[4 * row + column] = GET_K_MATRIX(info)[3 * row + column];
91  if (row == column)
92  {
93  GET_R_MATRIX(info)[3 * row + column] = 1.0f;
94  }
95  }
96  }
97 }
98 
99 void MonoCamera::onRequestData(ensenso::action::RequestDataMonoGoalConstPtr const& goal)
100 {
101  START_NXLIB_ACTION(RequestDataMono, requestDataServer)
102 
103  ensenso::action::RequestDataMonoResult result;
104  ensenso::action::RequestDataMonoFeedback feedback;
105 
106  bool publishResults = goal->publish_results;
107  if (!goal->publish_results && !goal->include_results_in_response)
108  {
109  publishResults = true;
110  }
111 
112  bool requestRectified = goal->request_rectified_images;
113  if (!goal->request_rectified_images && !goal->request_raw_images)
114  {
115  requestRectified = true;
116  }
117 
118  capture();
119 
121 
122  feedback.images_acquired = true;
123  requestDataServer->publishFeedback(feedback);
124 
125  if (goal->request_raw_images)
126  {
127  auto rawImages = imagesFromNxLibNode(cameraNode[itmImages][itmRaw], params.cameraFrame, params.isFileCamera);
128  cameraInfo->header.stamp = rawImages[0]->header.stamp;
129  cameraInfo->header.frame_id = params.cameraFrame;
130  if (goal->include_results_in_response)
131  {
132  for (auto const& image : rawImages)
133  {
134  result.raw_images.push_back(*image);
135  }
136  result.camera_info = *cameraInfo;
137  }
138  if (publishResults)
139  {
140  rawImagePublisher.publish(rawImages[0], cameraInfo);
141  }
142  }
143 
145 
146  if (requestRectified)
147  {
148  NxLibCommand rectify(cmdRectifyImages, params.serial);
149  rectify.parameters()[itmCameras] = params.serial;
150  rectify.execute();
151 
152  auto rectifiedImages =
154  rectifiedCameraInfo->header.stamp = rectifiedImages[0]->header.stamp;
155  rectifiedCameraInfo->header.frame_id = params.cameraFrame;
156  if (goal->include_results_in_response)
157  {
158  for (auto const& image : rectifiedImages)
159  {
160  result.rectified_images.push_back(*image);
161  }
162  result.rectified_camera_info = *rectifiedCameraInfo;
163  }
164  if (publishResults)
165  {
167  }
168  }
169 
170  requestDataServer->setSucceeded(std::move(result));
171 
172  FINISH_NXLIB_ACTION(RequestDataMono)
173 }
174 
175 void MonoCamera::onSetParameter(ensenso::action::SetParameterGoalConstPtr const& goal)
176 {
178 
179  ensenso::action::SetParameterResult result;
180 
181  loadParameterSet(goal->parameter_set);
182 
183  result.parameter_file_applied = false;
184  if (!goal->parameter_file.empty())
185  {
186  result.parameter_file_applied = loadSettings(goal->parameter_file);
187  if (!result.parameter_file_applied)
188  {
189  server->setAborted(std::move(result));
190  return;
191  }
192  }
193 
194  for (auto const& parameter : goal->parameters)
195  {
196  writeParameter(parameter);
197  }
198 
199  // Synchronize to make sure that we read back the correct values.
200  NxLibCommand synchronize(cmdSynchronize, params.serial);
201  synchronize.parameters()[itmCameras] = params.serial;
202  synchronize.execute();
203 
204  saveParameterSet(goal->parameter_set);
205 
206  // Calibration could have changed after setting new parameters.
208 
209  // Read back the actual values.
210  for (auto const& parameter : goal->parameters)
211  {
212  result.results.push_back(*readParameter(parameter.key));
213  }
214 
215  setParameterServer->setSucceeded(std::move(result));
216 
217  FINISH_NXLIB_ACTION(SetParameter)
218 }
219 
220 void MonoCamera::onLocatePattern(ensenso::action::LocatePatternMonoGoalConstPtr const& goal)
221 {
222  START_NXLIB_ACTION(LocatePatternMono, locatePatternServer)
223 
224  ensenso::action::LocatePatternMonoResult result;
225  ensenso::action::LocatePatternMonoFeedback feedback;
226 
227  loadParameterSet(goal->parameter_set);
228 
229  int numberOfShots = goal->number_of_shots;
230  if (numberOfShots < 1)
231  {
232  numberOfShots = 1;
233  }
234 
235  std::vector<MonoCalibrationPattern> patterns;
236  ensenso::ros::Time imageTimestamp;
237  for (int i = 0; i < numberOfShots; i++)
238  {
240 
241  ensenso::ros::Time timestamp = capture();
242  if (i == 0)
243  imageTimestamp = timestamp;
244 
246 
247  if (i == (numberOfShots - 1))
248  {
249  // The last image has been captured.
250  feedback.images_acquired = true;
251  locatePatternServer->publishFeedback(feedback);
252  }
253 
254  bool clearBuffer = (i == 0);
255  patterns = collectPattern(clearBuffer);
256  if (patterns.empty())
257  {
258  result.found_pattern = false;
259  locatePatternServer->setSucceeded(std::move(result));
260  return;
261  }
262 
263  if (patterns.size() > 1)
264  {
265  // Cannot average multiple shots of multiple patterns. We will cancel the capturing and estimate the pose of each
266  // pattern individually.
267  break;
268  }
269  }
270 
271  result.found_pattern = true;
272  result.mono_patterns.resize(patterns.size());
273  for (size_t i = 0; i < patterns.size(); i++)
274  {
275  patterns[i].writeToMessage(result.mono_patterns[i]);
276  }
277 
279 
280  std::string patternFrame = params.targetFrame;
281  if (!goal->target_frame.empty())
282  {
283  patternFrame = goal->target_frame;
284  }
285 
286  result.frame = patternFrame;
287 
288  if (patterns.size() > 1)
289  {
290  // Estimate the pose of all the patterns we found.
291  auto patternPoses = estimatePatternPoses(imageTimestamp, patternFrame);
292 
293  result.mono_pattern_poses.resize(patternPoses.size());
294  for (size_t i = 0; i < patternPoses.size(); i++)
295  {
296  result.mono_pattern_poses[i] = patternPoses[i];
297  }
298  }
299  else
300  {
301  // Estimate the pose of a single pattern, averaging over the different shots.
302  auto patternPose = estimatePatternPose(imageTimestamp, patternFrame);
303 
304  result.mono_pattern_poses.resize(1);
305  result.mono_pattern_poses[0] = patternPose;
306  }
307 
308  if (!goal->tf_frame.empty())
309  {
310  if (patterns.size() == 1)
311  {
312  geometry_msgs::msg::TransformStamped transform = transformFromPose(result.mono_pattern_poses[0], goal->tf_frame);
313  transformBroadcaster->sendTransform(transform);
314  }
315  else
316  {
317  ENSENSO_WARN(nh, "Cannot publish the pattern pose in tf, because there are multiple patterns!");
318  }
319  }
320 
321  locatePatternServer->setSucceeded(std::move(result));
322 
323  FINISH_NXLIB_ACTION(LocatePatternMono)
324 }
325 
326 std::vector<MonoCalibrationPattern> MonoCamera::collectPattern(bool clearBuffer) const
327 {
328  if (clearBuffer)
329  {
330  NxLibCommand(cmdDiscardPatterns, params.serial).execute();
331  }
332 
333  NxLibCommand collectPattern(cmdCollectPattern, params.serial);
334  collectPattern.parameters()[itmCameras] = params.serial;
335  collectPattern.parameters()[itmDecodeData] = true;
336  try
337  {
338  collectPattern.execute();
339  }
340  catch (NxLibException& e)
341  {
342  if (e.getErrorCode() == NxLibExecutionFailed)
343  {
344  if (collectPattern.result()[itmErrorSymbol] == errPatternNotFound ||
345  collectPattern.result()[itmErrorSymbol] == errPatternNotDecodable)
346  {
347  return {};
348  }
349  }
350  throw;
351  }
352 
353  std::vector<MonoCalibrationPattern> result;
354 
355  for (int i = 0; i < collectPattern.result()[itmPatterns][0][params.serial].count(); i++)
356  {
357  result.emplace_back(collectPattern.result()[itmPatterns][0][params.serial][i][itmPattern]);
358  }
359 
360  // Extract the pattern's image points from the result.
361  NxLibItem pattern = collectPattern.result()[itmPatterns][0][params.serial];
362 
363  for (size_t i = 0; i < result.size(); i++)
364  {
365  for (int j = 0; j < pattern[i][itmPoints].count(); j++)
366  {
367  NxLibItem pointNode = pattern[i][itmPoints][j];
368 
369  ensenso::msg::ImagePoint point;
370  point.x = pointNode[0].asDouble();
371  point.y = pointNode[1].asDouble();
372  result[i].points.push_back(point);
373  }
374  }
375 
376  return result;
377 }
378 
379 geometry_msgs::msg::PoseStamped MonoCamera::estimatePatternPose(ensenso::ros::Time imageTimestamp,
380  std::string const& targetFrame,
381  bool latestPatternOnly) const
382 {
383  updateGlobalLink(imageTimestamp, targetFrame);
384 
385  NxLibCommand estimatePatternPose(cmdEstimatePatternPose, params.serial);
386  estimatePatternPose.parameters()[itmType] = itmMonocular;
387  if (latestPatternOnly)
388  {
389  estimatePatternPose.parameters()[itmAverage] = false;
390 
391  int patternCount = NxLibItem()[itmParameters][itmPatternCount].asInt();
392  estimatePatternPose.parameters()[itmFilter][itmOr][0][itmAnd][0][itmType] = valIndex;
393  estimatePatternPose.parameters()[itmFilter][itmOr][0][itmAnd][0][itmValue] = patternCount - 1;
394  }
395  else
396  {
397  estimatePatternPose.parameters()[itmAverage] = true;
398  }
399  estimatePatternPose.execute();
400 
401  auto patterns = estimatePatternPose.result()[itmPatterns];
402  ENSENSO_ASSERT(patterns.count() == 1);
403 
404  return stampedPoseFromNxLib(patterns[0][itmPatternPose], targetFrame, imageTimestamp);
405 }
406 
407 std::vector<geometry_msgs::msg::PoseStamped> MonoCamera::estimatePatternPoses(ensenso::ros::Time imageTimestamp,
408  std::string const& targetFrame) const
409 {
410  updateGlobalLink(imageTimestamp, targetFrame);
411 
412  NxLibCommand estimatePatternPose(cmdEstimatePatternPose, params.serial);
413  estimatePatternPose.parameters()[itmAverage] = false;
414  estimatePatternPose.parameters()[itmType] = itmMonocular;
415  estimatePatternPose.parameters()[itmFilter][itmCameras] = params.serial;
416 
417  estimatePatternPose.execute();
418 
419  auto patterns = estimatePatternPose.result()[itmPatterns];
420 
421  std::vector<geometry_msgs::msg::PoseStamped> result;
422  result.reserve(patterns.count());
423 
424  for (int i = 0; i < patterns.count(); i++)
425  {
426  result.push_back(stampedPoseFromNxLib(patterns[i][itmPatternPose], targetFrame, imageTimestamp));
427  }
428 
429  return result;
430 }
GET_R_MATRIX
#define GET_R_MATRIX(info)
Definition: namespace.h:57
ENSENSO_WARN
void ENSENSO_WARN(T... args)
Definition: logging.h:210
stampedPoseFromNxLib
StampedPoseMsg stampedPoseFromNxLib(NxLibItem const &node, std::string const &parentFrame, ensenso::ros::Time timestamp)
Definition: pose_utilities.cpp:159
MonoCamera::onSetParameter
void onSetParameter(ensenso::action::SetParameterGoalConstPtr const &goal) override
Definition: mono_camera.cpp:175
Camera::fillBasicCameraInfoFromNxLib
void fillBasicCameraInfoFromNxLib(sensor_msgs::msg::CameraInfoPtr const &info) const
Definition: camera.cpp:324
Camera::params
CameraParameters params
Definition: camera.h:258
GET_P_MATRIX
#define GET_P_MATRIX(info)
Definition: namespace.h:56
MonoCamera::startServers
void startServers() const override
Definition: mono_camera.cpp:28
MonoCamera::requestDataServer
std::unique_ptr< RequestDataMonoServer > requestDataServer
Definition: mono_camera.h:15
MonoCamera::estimatePatternPose
geometry_msgs::msg::PoseStamped estimatePatternPose(ensenso::ros::Time imageTimestamp, std::string const &targetFrame="", bool latestPatternOnly=false) const override
Definition: mono_camera.cpp:379
Camera
Definition: camera.h:255
timestampFromNxLibNode
ensenso::ros::Time timestampFromNxLibNode(NxLibItem const &node)
Definition: image_utilities.cpp:174
fillDistortionParamsFromNxLib
void fillDistortionParamsFromNxLib(NxLibItem const &distortionItem, sensor_msgs::msg::CameraInfoPtr const &info)
Definition: image_utilities.cpp:206
START_NXLIB_ACTION
#define START_NXLIB_ACTION(ACTION_NAME, ACTION_SERVER)
Definition: camera.h:93
MonoCamera::capture
ensenso::ros::Time capture() const override
Definition: mono_camera.cpp:35
PREEMPT_ACTION_IF_REQUESTED
#define PREEMPT_ACTION_IF_REQUESTED
Definition: camera.h:136
CameraParameters
Definition: camera.h:175
MonoCamera::collectPattern
std::vector< MonoCalibrationPattern > collectPattern(bool clearBuffer=false) const
Definition: mono_camera.cpp:326
image_transport::CameraPublisher::publish
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
FINISH_NXLIB_ACTION
#define FINISH_NXLIB_ACTION(ACTION_NAME)
Definition: camera.h:104
MonoCamera::updateCameraInfo
void updateCameraInfo() override
Definition: mono_camera.cpp:64
MonoCamera::onRequestData
void onRequestData(ensenso::action::RequestDataMonoGoalConstPtr const &goal)
Definition: mono_camera.cpp:99
MonoCamera::rectifiedCameraInfo
sensor_msgs::msg::CameraInfoPtr rectifiedCameraInfo
Definition: mono_camera.h:13
Camera::loadParameterSet
void loadParameterSet(std::string name)
Definition: camera.cpp:615
Camera::writeParameter
virtual void writeParameter(ensenso::msg::Parameter const &parameter)
Definition: camera.cpp:445
CameraParameters::isFileCamera
bool isFileCamera
Definition: camera.h:186
Camera::saveParameterSet
void saveParameterSet(std::string name)
Definition: camera.cpp:602
ENSENSO_DEBUG
void ENSENSO_DEBUG(T... args)
Definition: logging.h:74
MonoCamera::init
void init() override
Definition: mono_camera.cpp:20
MonoCamera::advertiseTopics
void advertiseTopics()
Definition: mono_camera.cpp:14
mono_camera.h
Camera::startServers
virtual void startServers() const
Definition: camera.cpp:120
CameraParameters::serial
std::string serial
Definition: camera.h:180
Camera::transformBroadcaster
std::unique_ptr< tf2_ros::TransformBroadcaster > transformBroadcaster
Definition: camera.h:280
MonoCamera::rawImagePublisher
image_transport::CameraPublisher rawImagePublisher
Definition: mono_camera.h:18
ensenso::image_transport::create_camera_publisher
inline ::image_transport::CameraPublisher create_camera_publisher(ensenso::ros::NodeHandle const &nh, ::std::string const &topic_name)
Definition: image_transport.h:64
GET_D_MATRIX
#define GET_D_MATRIX(info)
Definition: namespace.h:54
MAKE_MONO_SERVER
#define MAKE_MONO_SERVER(CallbackClass, ActionName, TopicName)
Definition: action_server.h:39
MonoCamera::locatePatternServer
std::unique_ptr< LocatePatternMonoServer > locatePatternServer
Definition: mono_camera.h:16
Camera::loadSettings
bool loadSettings(std::string const &jsonFile, bool saveAsDefaultParameters=false)
Definition: camera.cpp:129
ensenso::ros::NodeHandle
::ros::NodeHandle NodeHandle
Definition: node.h:215
pose_utilities.h
ensenso::ros::Time
::ros::Time Time
Definition: time.h:67
Camera::initStatusTimer
virtual void initStatusTimer()
Definition: camera.cpp:704
Camera::initTfPublishTimer
virtual void initTfPublishTimer()
Definition: camera.cpp:699
CameraParameters::captureTimeout
int captureTimeout
Definition: camera.h:245
imagesFromNxLibNode
std::vector< ImagePtr > imagesFromNxLibNode(NxLibItem const &node, std::string const &frame, bool isFileCamera)
Definition: image_utilities.cpp:155
MonoCamera
Definition: mono_camera.h:9
ENSENSO_ASSERT
#define ENSENSO_ASSERT(cond)
Definition: core.h:166
ensenso::ros::now
inline ::ros::Time now(ensenso::ros::NodeHandle const &nh)
Definition: time.h:76
MonoCamera::rectifiedImagePublisher
image_transport::CameraPublisher rectifiedImagePublisher
Definition: mono_camera.h:19
MonoCamera::onLocatePattern
void onLocatePattern(ensenso::action::LocatePatternMonoGoalConstPtr const &goal)
Definition: mono_camera.cpp:220
Camera::readParameter
virtual ensenso::msg::ParameterPtr readParameter(std::string const &key) const
Definition: camera.cpp:406
std
MonoCamera::fillCameraInfoFromNxLib
void fillCameraInfoFromNxLib(sensor_msgs::msg::CameraInfoPtr const &info, bool rectified=false)
Definition: mono_camera.cpp:70
Camera::cameraNode
NxLibItem cameraNode
Definition: camera.h:266
transformFromPose
StampedTransformMsg transformFromPose(StampedPoseMsg const &pose, std::string const &childFrame)
Definition: pose_utilities.cpp:173
GET_K_MATRIX
#define GET_K_MATRIX(info)
Definition: namespace.h:55
CameraParameters::targetFrame
std::string targetFrame
Definition: camera.h:227
MonoCamera::estimatePatternPoses
std::vector< geometry_msgs::msg::PoseStamped > estimatePatternPoses(ensenso::ros::Time imageTimestamp, std::string const &targetFrame="") const override
Definition: mono_camera.cpp:407
MonoCamera::cameraInfo
sensor_msgs::msg::CameraInfoPtr cameraInfo
Definition: mono_camera.h:12
Camera::setParameterServer
std::unique_ptr< SetParameterServer > setParameterServer
Definition: camera.h:285
MonoCamera::MonoCamera
MonoCamera(ensenso::ros::NodeHandle &nh, CameraParameters params)
Definition: mono_camera.cpp:5
Camera::nh
ensenso::ros::NodeHandle nh
Definition: camera.h:271
CameraParameters::cameraFrame
std::string cameraFrame
Definition: camera.h:206
Camera::updateGlobalLink
void updateGlobalLink(ensenso::ros::Time time, std::string targetFrame="", bool useCachedTransformation=false) const
Definition: camera.cpp:362
move
void move(std::vector< T > &a, std::vector< T > &b)


ensenso_camera
Author(s): Ensenso
autogenerated on Wed Apr 2 2025 02:37:46