trigger_node.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012 Jack O'Quin
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the author nor other contributors may be
18 * used to endorse or promote products derived from this software
19 * without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #include <signal.h>
36 #include <dc1394/dc1394.h>
37 #include <ros/ros.h>
38 
50 void sigsegv_handler(int sig)
51 {
52  signal(SIGSEGV, SIG_DFL);
53  fprintf(stderr, "Segmentation fault, stopping camera driver.\n");
54  ROS_FATAL("Segmentation fault, stopping camera.");
55  ros::shutdown(); // stop the main loop
56 }
57 
59 {
60 public:
61 
63  camera_(NULL)
64  {}
65 
73  bool setup(void)
74  {
75  dc1394_t *dev = dc1394_new();
76  if (dev == NULL)
77  {
78  ROS_FATAL("Failed to initialize dc1394_context.");
79  return false;
80  }
81 
82  // list all 1394 cameras attached to this computer
83  dc1394camera_list_t *cameras;
84  int err = dc1394_camera_enumerate(dev, &cameras);
85  if (err != DC1394_SUCCESS)
86  {
87  ROS_FATAL("Could not get list of cameras");
88  return false;
89  }
90  if (cameras->num == 0)
91  {
92  ROS_FATAL("No cameras found");
93  return false;
94  }
95 
96  // attach to first camera found
97  ROS_INFO_STREAM("Connecting to first camera, GUID: "
98  << std::setw(16) << std::setfill('0') << std::hex
99  << cameras->ids[0].guid);
100  camera_ = dc1394_camera_new(dev, cameras->ids[0].guid);
101  if (!camera_)
102  {
103  ROS_FATAL("Failed to initialize camera.");
104  return false;
105  }
106 
107  dc1394_camera_free_list(cameras);
108  return true;
109  }
110 
112  bool spin(void)
113  {
114  bool retval = true;
115  ros::Rate hz(2.0);
116  while (node_.ok())
117  {
118  ros::spinOnce();
119  if (!trigger())
120  {
121  retval = false;
122  break;
123  }
124  hz.sleep();
125  }
126  shutdown();
127  return retval;
128  }
129 
130 private:
131 
133  void shutdown(void)
134  {
135  dc1394_camera_free(camera_);
136  camera_ = NULL;
137  }
138 
142  bool trigger(void)
143  {
144  dc1394error_t err = dc1394_software_trigger_set_power(camera_, DC1394_ON);
145  bool retval = (err == DC1394_SUCCESS);
146  if (!retval)
147  ROS_FATAL("camera does not provide software trigger");
148  return retval;
149  }
150 
152  dc1394camera_t *camera_;
153 };
154 
156 int main(int argc, char **argv)
157 {
158  ros::init(argc, argv, "camera1394_trigger_node");
159  signal(SIGSEGV, &sigsegv_handler);
160 
161  TriggerNode trig;
162 
163  if (!trig.setup()) // device connection failed?
164  return 1;
165 
166  if (!trig.spin()) // device does not support trigger?
167  return 2;
168 
169  return 0;
170 }
#define ROS_FATAL(...)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::NodeHandle node_
bool spin(void)
void sigsegv_handler(int sig)
bool sleep()
dc1394camera_t * camera_
#define ROS_INFO_STREAM(args)
void shutdown(void)
ROSCPP_DECL void shutdown()
bool trigger(void)
bool ok() const
bool setup(void)
ROSCPP_DECL void spinOnce()
int main(int argc, char **argv)


camera1394
Author(s): Jack O'Quin, Ken Tossell, Patrick Beeson, Nate Koenig, Andrew Howard, Damien Douxchamps, Dan Dennedy
autogenerated on Mon Jun 10 2019 12:52:31