nerian_stereo_node.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2  * Copyright (c) 2019 Nerian Vision GmbH
3  *
4  * Permission is hereby granted, free of charge, to any person obtaining a copy
5  * of this software and associated documentation files (the "Software"), to deal
6  * in the Software without restriction, including without limitation the rights
7  * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
8  * copies of the Software, and to permit persons to whom the Software is
9  * furnished to do so, subject to the following conditions:
10  *
11  * The above copyright notice and this permission notice shall be included in
12  * all copies or substantial portions of the Software.
13  *******************************************************************************/
14 
16 
17 namespace nerian_stereo {
18 
19 class StereoNode: public StereoNodeBase {
20 public:
22 
26  int run() {
28  try {
29  while(ros::ok()) {
30  // Dispatch any queued ROS callbacks
31  ros::spinOnce();
32  // Get a single image pair and process it
34  }
35  } catch(const std::exception& ex) {
36  ROS_FATAL("Exception occured: %s", ex.what());
37  return 1;
38  }
39  return 0;
40  }
41 private:
42  // The standalone node has its own private node handles
45  inline ros::NodeHandle& getNH() override { return nhInternal; }
46  inline ros::NodeHandle& getPrivateNH() override { return privateNhInternal; }
47 };
48 
49 } // namespace
50 
51 int main(int argc, char** argv) {
52  try {
53  ros::init(argc, argv, "nerian_stereo");
55  node.init();
57  return node.run();
58  } catch(const std::exception& ex) {
59  ROS_FATAL("Exception occured: %s", ex.what());
60  return 1;
61  }
62 }
63 
void prepareAsyncTransfer()
Connects to the image service to request the stream of image pairs.
ros::NodeHandle & getNH() override
#define ROS_FATAL(...)
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL bool ok()
A driver node that receives data from SceneScan/SP1 and forwards it to ROS.
ros::NodeHandle & getPrivateNH() override
ROSCPP_DECL void spinOnce()
int run()
The main loop of this node.
void init()
Performs general initializations.


nerian_stereo
Author(s): Nerian Vision Technologies
autogenerated on Thu Jun 20 2019 19:12:46