cv_camera_node.cpp
Go to the documentation of this file.
1 // Copyright [2015] Takashi Ogura<t.ogura@gmail.com>
2 
3 #include "cv_camera/driver.h"
4 
5 int main(int argc, char **argv)
6 {
7  ros::init(argc, argv, "cv_camera");
8  ros::NodeHandle private_node("~");
9  cv_camera::Driver driver(private_node, private_node);
10 
11  try
12  {
13  driver.setup();
14  while (ros::ok())
15  {
16  driver.proceed();
17  ros::spinOnce();
18  }
19  }
20  catch (cv_camera::DeviceError &e)
21  {
22  ROS_ERROR_STREAM("cv camera open failed: " << e.what());
23  return 1;
24  }
25 
26  return 0;
27 }
ROS cv camera device exception.
Definition: exception.h:16
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL bool ok()
void proceed()
Capture, publish and sleep.
Definition: driver.cpp:100
ROS cv camera driver.
Definition: driver.h:16
int main(int argc, char **argv)
void setup()
Setup camera device and ROS parameters.
Definition: driver.cpp:21
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void spinOnce()


cv_camera
Author(s): Takashi Ogura
autogenerated on Mon Jun 1 2020 03:55:59