camera.cpp
Go to the documentation of this file.
2 
6 
8 
9 ParameterSet::ParameterSet(const std::string& name, const NxLibItem& defaultParameters)
10 {
11  // Create a new NxLib node where we will store the parameters for this set and
12  // overwrite it with the default settings.
13  node = NxLibItem()["rosParameterSets"][name];
14  node << defaultParameters;
15 }
16 
17 Camera::Camera(ros::NodeHandle const& n, std::string serial, std::string fileCameraPath, bool fixed,
18  std::string cameraFrame, std::string targetFrame, std::string linkFrame)
19  : fileCameraPath(std::move(fileCameraPath))
20  , serial(std::move(serial))
21  , fixed(fixed)
22  , cameraFrame(std::move(cameraFrame))
23  , linkFrame(std::move(linkFrame))
24  , targetFrame(std::move(targetFrame))
25  , nh(n)
26 {
27  transformListener = make_unique<tf2_ros::TransformListener>(tfBuffer);
28  transformBroadcaster = make_unique<tf2_ros::TransformBroadcaster>();
29 
30  isFileCamera = !this->fileCameraPath.empty();
31 
32  accessTreeServer = make_unique<AccessTreeServer>(nh, "access_tree", boost::bind(&Camera::onAccessTree, this, _1));
34  make_unique<ExecuteCommandServer>(nh, "execute_command", boost::bind(&Camera::onExecuteCommand, this, _1));
36  make_unique<GetParameterServer>(nh, "get_parameter", boost::bind(&Camera::onGetParameter, this, _1));
38  make_unique<SetParameterServer>(nh, "set_parameter", boost::bind(&Camera::onSetParameter, this, _1));
39 
40  statusPublisher = nh.advertise<diagnostic_msgs::DiagnosticArray>("/diagnostics", 1);
41 
42  cameraNode = NxLibItem()[itmCameras][itmBySerialNo][this->serial];
43 
44  defaultParameters = NxLibItem()["rosDefaultParameters"];
45 }
46 
48 {
49  accessTreeServer->start();
50  executeCommandServer->start();
51 
52  getParameterServer->start();
53  setParameterServer->start();
54 }
55 
56 bool Camera::loadSettings(const std::string& jsonFile, bool saveAsDefaultParameters)
57 {
58  if (jsonFile.empty())
59  return true;
60 
61  std::ifstream file(jsonFile);
62  if (file.is_open() && file.rdbuf())
63  {
64  std::stringstream buffer;
65  buffer << file.rdbuf();
66  std::string const& jsonSettings = buffer.str();
67 
68  NxLibItem tmpParameters = NxLibItem()["rosTemporaryParameters"];
69  try
70  {
71  tmpParameters.setJson(jsonSettings);
72  }
73  catch (NxLibException&)
74  {
75  ROS_ERROR("The file '%s' does not contain valid JSON", jsonFile.c_str());
76  return false;
77  }
78 
79  try
80  {
81  if (tmpParameters[itmParameters].exists())
82  {
83  // The file contains the entire camera node.
84  cameraNode[itmParameters] << tmpParameters[itmParameters];
85  }
86  else
87  {
88  // The file contains only the parameter node.
89  cameraNode[itmParameters].setJson(jsonSettings, true);
90  }
91  tmpParameters.erase();
92 
93  NxLibCommand synchronize(cmdSynchronize, serial);
94  synchronize.parameters()[itmCameras] = serial;
95  synchronize.execute();
96 
98  if (saveAsDefaultParameters)
100  }
101  catch (NxLibException& e)
102  {
104  return false;
105  }
106  }
107  else
108  {
109  ROS_ERROR("Could not open the file '%s'", jsonFile.c_str());
110  return false;
111  }
112 
113  return true;
114 }
115 
116 void Camera::onAccessTree(const ensenso_camera_msgs::AccessTreeGoalConstPtr& goal)
117 {
119 
120  loadParameterSet(goal->parameter_set);
121 
122  NxLibItem item(goal->path);
123 
124  bool treeChanged = false;
125  if (goal->erase)
126  {
127  item.erase();
128  treeChanged = true;
129  }
130  else if (goal->set_null)
131  {
132  item.setNull();
133  treeChanged = true;
134  }
135  else if (!goal->json_value.empty())
136  {
137  item.setJson(goal->json_value);
138  treeChanged = true;
139  }
140 
141  if (treeChanged)
142  {
143  saveParameterSet(goal->parameter_set);
144  }
145 
146  ensenso_camera_msgs::AccessTreeResult result;
147 
148  result.exists = false;
149  if (item.exists())
150  {
151  result.exists = true;
152 
153  result.json_value = item.asJson();
154  try
155  {
156  // This could load any image that does not belong to the node's camera,
157  // so we do not know its frame.
158  result.binary_data = *imageFromNxLibNode(item, "");
159  }
160  catch (NxLibException&)
161  {
162  } // The item was not binary.
163  }
164 
165  accessTreeServer->setSucceeded(result);
166 
167  FINISH_NXLIB_ACTION(AccessTree)
168 }
169 
170 void Camera::onExecuteCommand(const ensenso_camera_msgs::ExecuteCommandGoalConstPtr& goal)
171 {
173 
174  loadParameterSet(goal->parameter_set);
175 
176  NxLibCommand command(goal->command);
177  command.parameters().setJson(goal->parameters);
178  command.execute();
179 
180  ensenso_camera_msgs::ExecuteCommandResult result;
181  result.result = command.result().asJson();
182 
183  executeCommandServer->setSucceeded(result);
184 
185  FINISH_NXLIB_ACTION(ExecuteCommand)
186 }
187 
188 void Camera::onGetParameter(ensenso_camera_msgs::GetParameterGoalConstPtr const& goal)
189 {
191 
192  ensenso_camera_msgs::GetParameterResult result;
193 
194  loadParameterSet(goal->parameter_set);
195 
196  result.stamp = ros::Time::now();
197  for (auto const& key : goal->keys)
198  {
199  result.results.push_back(*readParameter(key));
200  }
201 
202  getParameterServer->setSucceeded(result);
203 
204  FINISH_NXLIB_ACTION(GetParameter)
205 }
206 
208 {
209  return cameraNode[itmStatus].exists() && cameraNode[itmStatus][itmAvailable].exists() &&
210  cameraNode[itmStatus][itmAvailable].asBool();
211 }
212 
214 {
215  return cameraNode[itmStatus].exists() && cameraNode[itmStatus][itmOpen].exists() &&
216  cameraNode[itmStatus][itmOpen].asBool();
217 }
218 
219 void Camera::publishStatus(ros::TimerEvent const& event) const
220 {
221  std::lock_guard<std::mutex> lock(nxLibMutex);
222 
223  diagnostic_msgs::DiagnosticStatus cameraStatus;
224  cameraStatus.name = "Camera";
225  cameraStatus.hardware_id = serial;
226  cameraStatus.level = diagnostic_msgs::DiagnosticStatus::OK;
227  cameraStatus.message = "OK";
228 
229  if (!cameraIsOpen())
230  {
231  cameraStatus.level = diagnostic_msgs::DiagnosticStatus::ERROR;
232  cameraStatus.message = "Camera is no longer open";
233  }
234 
235  diagnostic_msgs::DiagnosticArray status;
236  status.header.stamp = ros::Time::now();
237  status.status.push_back(cameraStatus);
238  statusPublisher.publish(status);
239 }
240 
241 void Camera::fillBasicCameraInfoFromNxLib(sensor_msgs::CameraInfoPtr const& info) const
242 {
243  info->header.frame_id = cameraFrame;
244 
245  info->width = cameraNode[itmSensor][itmSize][0].asInt();
246  info->height = cameraNode[itmSensor][itmSize][1].asInt();
247 
248  info->binning_x = cameraNode[itmParameters][itmCapture][itmBinning].asInt();
249  info->binning_y = info->binning_x;
250 }
251 
252 void Camera::updateTransformations(tf2::Transform const& targetFrameTransformation) const
253 {
254  cameraNode[itmLink][itmTarget] = TARGET_FRAME_LINK + "_" + serial;
255  writePoseToNxLib(targetFrameTransformation, NxLibItem()[itmLinks][TARGET_FRAME_LINK + "_" + serial]);
256 }
257 
258 void Camera::updateGlobalLink(ros::Time time, std::string frame, bool useCachedTransformation) const
259 {
260  if (frame.empty())
261  {
262  frame = targetFrame;
263  }
264 
265  // Transformation are represented in the NxLib as follows.
266  // The camera's link node contains the calibration data from e.g. the hand
267  // eye calibration. This is always used when it is present.
268  // The transformation between the camera frame and the target frame (in
269  // which the data is returned) is fetched from TF and written to a link node
270  // of the NxLib. When the target frame is different from the camera's own
271  // frame, we set the camera's link target to this link node.
272 
273  if (cameraFrame == frame)
274  {
275  // The camera frame is the target frame already. No need to transform
276  // anything in the NxLib.
277  cameraNode[itmLink][itmTarget] = "";
278  return;
279  }
280 
281  cameraNode[itmLink][itmTarget] = TARGET_FRAME_LINK + "_" + serial;
282 
283  // Update the transformation to the target frame in the NxLib according to
284  // the current information from TF. Only if the link frame and target frame differs. Otherwise the transformation will
285  // be doubled. If they're the same, the global Link must be the identity transform and the tf will be in the camera
286  // link. (camera -> link in Nxlib or link -> camera in ROS).
287  if (targetFrame != linkFrame)
288  {
289  geometry_msgs::TransformStamped transform;
290  if (useCachedTransformation && transformationCache.count(frame) != 0)
291  {
292  transform = transformationCache[frame];
293  }
294  else
295  {
297  transformationCache[frame] = transform;
298  }
299  tf2::Transform tfTrafo;
300  tf2::convert(transform.transform, tfTrafo);
301  NxLibItem()[itmLinks][TARGET_FRAME_LINK + "_" + serial].setNull();
302  NxLibItem()[itmLinks].setNull();
303  writePoseToNxLib(tfTrafo, NxLibItem()[itmLinks][TARGET_FRAME_LINK + "_" + serial]);
304  }
305 }
306 
307 std::vector<geometry_msgs::TransformStamped> Camera::estimatePatternPoses(ros::Time imageTimestamp,
308  std::string const& targetFrame) const
309 {
310  updateGlobalLink(imageTimestamp, targetFrame);
311 
312  NxLibCommand estimatePatternPose(cmdEstimatePatternPose, serial);
313  estimatePatternPose.parameters()[itmAverage] = false;
314  estimatePatternPose.parameters()[itmFilter][itmCameras] = serial;
315  estimatePatternPose.parameters()[itmFilter][itmUseModel] = true;
316  estimatePatternPose.parameters()[itmFilter][itmType] = valStatic;
317  estimatePatternPose.parameters()[itmFilter][itmValue] = true;
318  estimatePatternPose.execute();
319 
320  int numberOfPatterns = estimatePatternPose.result()[itmPatterns].count();
321 
322  std::vector<geometry_msgs::TransformStamped> result;
323  result.reserve(numberOfPatterns);
324 
325  for (int i = 0; i < numberOfPatterns; i++)
326  {
327  result.push_back(
328  poseFromNxLib(estimatePatternPose.result()[itmPatterns][i][itmPatternPose], cameraFrame, targetFrame));
329  }
330 
331  return result;
332 }
333 
334 geometry_msgs::TransformStamped Camera::estimatePatternPose(ros::Time imageTimestamp, std::string const& targetFrame,
335  bool latestPatternOnly) const
336 {
337  updateGlobalLink(imageTimestamp, targetFrame);
338 
339  NxLibCommand estimatePatternPose(cmdEstimatePatternPose, serial);
340  if (latestPatternOnly)
341  {
342  estimatePatternPose.parameters()[itmAverage] = false;
343 
344  int patternCount = NxLibItem()[itmParameters][itmPatternCount].asInt();
345  estimatePatternPose.parameters()[itmFilter][itmOr][0][itmAnd][0][itmType] = valIndex;
346  estimatePatternPose.parameters()[itmFilter][itmOr][0][itmAnd][0][itmValue] = patternCount - 1;
347  }
348  else
349  {
350  estimatePatternPose.parameters()[itmAverage] = true;
351  }
352  estimatePatternPose.execute();
353 
354  ROS_ASSERT(estimatePatternPose.result()[itmPatterns].count() == 1);
355 
356  return poseFromNxLib(estimatePatternPose.result()[itmPatterns][0][itmPatternPose], cameraFrame, targetFrame);
357 }
358 
359 ensenso_camera_msgs::ParameterPtr Camera::readParameter(std::string const& key) const
360 {
361  auto message = boost::make_shared<ensenso_camera_msgs::Parameter>();
362  message->key = key;
363  if (parameterExists(key))
364  {
365  // The parameter is mapped to an NxLib node.
366 
367  ParameterMapping parameterMapping = parameterInformation.at(key);
368  NxLibItem node = parameterMapping.node(cameraNode);
369 
370  if (node.exists())
371  {
372  switch (parameterMapping.type)
373  {
374  case ParameterType::Bool:
375  message->bool_value = node.asBool();
376  break;
378  message->float_value = node.asDouble();
379  break;
381  message->string_value = node.asString();
382  break;
383  }
384  }
385  else
386  {
387  ROS_WARN("Reading the parameter %s, but the camera does not support it!", key.c_str());
388  }
389  }
390  else
391  {
392  ROS_ERROR("Unknown parameter '%s'!", key.c_str());
393  }
394 
395  return message;
396 }
397 
398 void Camera::writeParameter(ensenso_camera_msgs::Parameter const& parameter)
399 {
400  if (parameterExists(parameter.key))
401  {
402  // The parameter is mapped to an NxLib node.
403 
404  ParameterMapping parameterMapping = parameterInformation.at(parameter.key);
405  NxLibItem node = parameterMapping.node(cameraNode);
406 
407  if (!node.exists())
408  {
409  ROS_WARN("Writing the parameter %s, but the camera does not support it!", parameter.key.c_str());
410  return;
411  }
412 
413  switch (parameterMapping.type)
414  {
415  case ParameterType::Bool:
416  node.set<bool>(parameter.bool_value);
417  break;
419  node.set<double>(parameter.float_value);
420  break;
422  node.set<std::string>(parameter.string_value);
423  }
424  }
425  else
426  {
427  ROS_ERROR("Unknown parameter '%s'!", parameter.key.c_str());
428  }
429 }
430 
432 {
433  if (isFileCamera && !cameraNode.exists())
434  {
435  try
436  {
437  if (serial.size() > 15)
438  {
439  ROS_ERROR("The serial '%s' is too long!", serial.c_str());
440  return false;
441  }
442 
443  NxLibCommand createCamera(cmdCreateCamera, serial);
444  createCamera.parameters()[itmSerialNumber] = serial;
445  createCamera.parameters()[itmFolderPath] = fileCameraPath;
446  createCamera.execute();
447 
448  createdFileCamera = true;
449  }
450  catch (NxLibException& e)
451  {
452  ROS_ERROR("Failed to create the file camera!");
454  return false;
455  }
456  }
457 
458  if (!cameraNode.exists())
459  {
460  ROS_ERROR("The camera '%s' could not be found", serial.c_str());
461  return false;
462  }
463  if (!cameraIsAvailable())
464  {
465  ROS_ERROR("The camera '%s' is already in use", serial.c_str());
466  return false;
467  }
468 
469  try
470  {
471  NxLibCommand open(cmdOpen, serial);
472  open.parameters()[itmCameras] = serial;
473  open.execute();
474  }
475  catch (NxLibException& e)
476  {
477  ROS_ERROR("Error while opening the camera '%s'!", serial.c_str());
479  return false;
480  }
481 
484 
485  ROS_INFO("Opened camera with serial number '%s'.", serial.c_str());
486  return true;
487 }
488 
490 {
491  std::lock_guard<std::mutex> lock(nxLibMutex);
492 
493  try
494  {
495  NxLibCommand close(cmdClose, serial);
496  close.parameters()[itmCameras] = serial;
497  close.execute();
498 
500  {
501  NxLibCommand deleteCmd(cmdDeleteCamera, serial);
502  deleteCmd.parameters()[itmCameras] = serial;
503  deleteCmd.execute();
504  }
505  }
506  catch (NxLibException&)
507  {
508  }
509 }
510 
512 {
513  defaultParameters << cameraNode[itmParameters];
514 }
515 
516 void Camera::saveParameterSet(std::string name)
517 {
518  if (name.empty())
519  {
520  name = DEFAULT_PARAMETER_SET;
521  }
522 
523  ParameterSet& parameterSet = parameterSets.at(name);
524 
525  parameterSet.node.erase();
526  parameterSet.node << cameraNode[itmParameters];
527 }
528 
529 void Camera::loadParameterSet(std::string name)
530 {
531  if (name.empty())
532  {
533  name = DEFAULT_PARAMETER_SET;
534  }
535 
536  ROS_DEBUG("Loading parameter set '%s'", name.c_str());
537 
538  if (parameterSets.count(name) == 0)
539  {
540  // The parameter set was never used before. Create it by copying the
541  // default settings.
542  parameterSets.insert(std::make_pair(name, ParameterSet(name, defaultParameters)));
543  }
544 
545  ParameterSet const& parameterSet = parameterSets.at(name);
546 
547  bool changedParameters = false;
548  if (name != currentParameterSet)
549  {
550  cameraNode[itmParameters] << parameterSet.node;
551  changedParameters = true;
552  }
553 
554  if (changedParameters)
555  {
556  NxLibCommand synchronize(cmdSynchronize, serial);
557  synchronize.parameters()[itmCameras] = serial;
558  synchronize.execute();
559  }
560 
561  currentParameterSet = name;
562 }
563 
565 {
567 }
568 
570 {
571  // The camera link is the calibrated link from camera to link
572  if (cameraFrame == linkFrame)
573  {
574  return;
575  }
576 
577  bool cameraLinkExists = cameraNode[itmLink][itmTarget].exists();
578 
579  if (cameraLinkExists)
580  {
581  transformBroadcaster->sendTransform(stampedLinkToCamera());
582  }
583 }
584 
585 geometry_msgs::TransformStamped Camera::stampedLinkToCamera()
586 {
588  // Need the inverse, because we want to publish the other way around
589  // E.g. Instead of camera->link, we want link->camera
590  // We also need the camera always to be the child frame
591  geometry_msgs::TransformStamped transformStamped = fromTfTransform(transform.inverse(), linkFrame, cameraFrame);
592  return transformStamped;
593 }
594 
596 {
597  // The Nxlib will always give the transfrom from the Camera to the Link target in Camera Coordinates.
598  tf2::Transform transform;
599  try
600  {
601  transform = poseFromNxLib(cameraNode[itmLink]);
602  }
603  catch (NxLibException const& e)
604  {
605  ROS_WARN("Link does not exists.Therefore we cannot publish a transform to any target. Error message: %s",
606  e.getErrorText().c_str());
607  }
608 
609  if (!isValid(transform))
610  {
611  transform.setIdentity();
612  ROS_WARN("Did not find a good transform from %s to %s. Transform has been set to identity", cameraFrame.c_str(),
613  linkFrame.c_str());
614  }
615 
616  return transform;
617 }
618 
620 {
622 }
623 
625 {
627 }
sensor_msgs::ImagePtr imageFromNxLibNode(NxLibItem const &node, std::string const &frame)
std::string const DEFAULT_PARAMETER_SET
Definition: camera.h:56
std::map< std::string, ParameterSet > parameterSets
Definition: camera.h:222
NxLibItem node
Definition: camera.h:155
std::string targetFrame
Definition: camera.h:198
virtual void initStatusTimer()
Definition: camera.cpp:624
void publish(const boost::shared_ptr< M > &message) const
bool parameterExists(std::string const &key)
Definition: parameters.h:87
void updateTransformations(tf2::Transform const &targetFrameTransformation) const
Definition: camera.cpp:252
ros::NodeHandle nh
Definition: camera.h:200
std::map< std::string, ParameterMapping > const parameterInformation
Definition: parameters.h:52
void updateGlobalLink(ros::Time time=ros::Time::now(), std::string frame="", bool useCachedTransformation=false) const
Definition: camera.cpp:258
geometry_msgs::TransformStamped stampedLinkToCamera()
Definition: camera.cpp:585
double const POSE_TF_INTERVAL
Definition: camera.h:45
std::string const TARGET_FRAME_LINK
Definition: camera.h:61
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
NxLibItem node(NxLibItem const &cameraNode)
Definition: parameters.h:33
virtual void publishStatus(ros::TimerEvent const &event) const
Definition: camera.cpp:219
double const STATUS_INTERVAL
Definition: camera.h:39
void publishCameraLink()
Definition: camera.cpp:569
ros::Publisher statusPublisher
Definition: camera.h:202
virtual bool open()
Definition: camera.cpp:431
ros::Timer cameraPosePublisher
Definition: camera.h:204
std::string cameraFrame
Definition: camera.h:196
NxLibItem defaultParameters
Definition: camera.h:220
bool cameraIsOpen() const
Definition: camera.cpp:213
#define ROS_WARN(...)
virtual std::vector< geometry_msgs::TransformStamped > estimatePatternPoses(ros::Time imageTimestamp=ros::Time::now(), std::string const &targetFrame="") const
Definition: camera.cpp:307
void setIdentity()
std::mutex nxLibMutex
Definition: camera.h:191
void writePoseToNxLib(tf2::Transform const &pose, NxLibItem const &node)
double const TRANSFORMATION_REQUEST_TIMEOUT
Definition: camera.h:50
std::unique_ptr< SetParameterServer > setParameterServer
Definition: camera.h:214
virtual void updateCameraInfo()=0
virtual void initTfPublishTimer()
Definition: camera.cpp:619
std::string serial
Definition: camera.h:187
ROSLIB_DECL std::string command(const std::string &cmd)
#define ROS_INFO(...)
tf2::Transform getCameraToLinkTransform()
Definition: camera.cpp:595
void publishCurrentLinks(ros::TimerEvent const &timerEvent=ros::TimerEvent())
Definition: camera.cpp:564
Camera(ros::NodeHandle const &n, std::string serial, std::string fileCameraPath, bool fixed, std::string cameraFrame, std::string targetFrame, std::string linkFrame)
Definition: camera.cpp:17
void onGetParameter(ensenso_camera_msgs::GetParameterGoalConstPtr const &goal)
Definition: camera.cpp:188
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Transform inverse() const
virtual geometry_msgs::TransformStamped estimatePatternPose(ros::Time imageTimestamp=ros::Time::now(), std::string const &targetFrame="", bool latestPatternOnly=false) const
Definition: camera.cpp:334
void onAccessTree(ensenso_camera_msgs::AccessTreeGoalConstPtr const &goal)
Definition: camera.cpp:116
virtual void writeParameter(ensenso_camera_msgs::Parameter const &parameter)
Definition: camera.cpp:398
bool isValid(tf2::Transform const &pose)
std::string fileCameraPath
Definition: camera.h:182
std::unique_ptr< ExecuteCommandServer > executeCommandServer
Definition: camera.h:212
bool isFileCamera
Definition: camera.h:181
NxLibItem cameraNode
Definition: camera.h:188
virtual void startServers() const
Definition: camera.cpp:47
bool createdFileCamera
Definition: camera.h:185
geometry_msgs::TransformStamped fromTfTransform(tf2::Transform const &transform, std::string parentFrame, std::string childFrame)
bool cameraIsAvailable() const
Definition: camera.cpp:207
void onExecuteCommand(ensenso_camera_msgs::ExecuteCommandGoalConstPtr const &goal)
Definition: camera.cpp:170
tf2_ros::Buffer tfBuffer
Definition: camera.h:207
virtual void onSetParameter(ensenso_camera_msgs::SetParameterGoalConstPtr const &goal)=0
void loadParameterSet(std::string name)
Definition: camera.cpp:529
std::string linkFrame
Definition: camera.h:197
#define LOG_NXLIB_EXCEPTION(EXCEPTION)
Definition: camera.h:68
ParameterSet(std::string const &name, NxLibItem const &defaultParameters)
Definition: camera.cpp:9
tf2::Transform poseFromNxLib(NxLibItem const &node)
void saveDefaultParameterSet()
Definition: camera.cpp:511
static Time now()
#define START_NXLIB_ACTION(ACTION_NAME, ACTION_SERVER)
Definition: camera.h:90
ros::Timer statusTimer
Definition: camera.h:203
void convert(const A &a, B &b)
std::unique_ptr< AccessTreeServer > accessTreeServer
Definition: camera.h:211
ROSCPP_DECL bool exists(const std::string &service_name, bool print_failure_reason)
std::map< std::string, geometry_msgs::TransformStamped > transformationCache
Definition: camera.h:217
std::unique_ptr< GetParameterServer > getParameterServer
Definition: camera.h:213
void saveParameterSet(std::string name)
Definition: camera.cpp:516
void fillBasicCameraInfoFromNxLib(sensor_msgs::CameraInfoPtr const &info) const
Definition: camera.cpp:241
#define ROS_ASSERT(cond)
virtual ensenso_camera_msgs::ParameterPtr readParameter(std::string const &key) const
Definition: camera.cpp:359
#define FINISH_NXLIB_ACTION(ACTION_NAME)
Definition: camera.h:101
std::string currentParameterSet
Definition: camera.h:223
ParameterType type
Definition: parameters.h:25
#define ROS_ERROR(...)
bool loadSettings(std::string const &jsonFile, bool saveAsDefaultParameters=false)
Definition: camera.cpp:56
std::unique_ptr< tf2_ros::TransformListener > transformListener
Definition: camera.h:208
#define ROS_DEBUG(...)
std::unique_ptr< tf2_ros::TransformBroadcaster > transformBroadcaster
Definition: camera.h:209
void close()
Definition: camera.cpp:489


ensenso_camera
Author(s): Ensenso
autogenerated on Mon Oct 21 2019 03:49:24