Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include <signal.h>
00036 #include <dc1394/dc1394.h>
00037 #include <ros/ros.h>
00038
00050 void sigsegv_handler(int sig)
00051 {
00052 signal(SIGSEGV, SIG_DFL);
00053 fprintf(stderr, "Segmentation fault, stopping camera driver.\n");
00054 ROS_FATAL("Segmentation fault, stopping camera.");
00055 ros::shutdown();
00056 }
00057
00058 class TriggerNode
00059 {
00060 public:
00061
00062 TriggerNode():
00063 camera_(NULL)
00064 {}
00065
00073 bool setup(void)
00074 {
00075 dc1394_t *dev = dc1394_new();
00076 if (dev == NULL)
00077 {
00078 ROS_FATAL("Failed to initialize dc1394_context.");
00079 return false;
00080 }
00081
00082
00083 dc1394camera_list_t *cameras;
00084 int err = dc1394_camera_enumerate(dev, &cameras);
00085 if (err != DC1394_SUCCESS)
00086 {
00087 ROS_FATAL("Could not get list of cameras");
00088 return false;
00089 }
00090 if (cameras->num == 0)
00091 {
00092 ROS_FATAL("No cameras found");
00093 return false;
00094 }
00095
00096
00097 ROS_INFO_STREAM("Connecting to first camera, GUID: "
00098 << std::setw(16) << std::setfill('0') << std::hex
00099 << cameras->ids[0].guid);
00100 camera_ = dc1394_camera_new(dev, cameras->ids[0].guid);
00101 if (!camera_)
00102 {
00103 ROS_FATAL("Failed to initialize camera.");
00104 return false;
00105 }
00106
00107 dc1394_camera_free_list(cameras);
00108 return true;
00109 }
00110
00112 bool spin(void)
00113 {
00114 bool retval = true;
00115 ros::Rate hz(2.0);
00116 while (node_.ok())
00117 {
00118 ros::spinOnce();
00119 if (!trigger())
00120 {
00121 retval = false;
00122 break;
00123 }
00124 hz.sleep();
00125 }
00126 shutdown();
00127 return retval;
00128 }
00129
00130 private:
00131
00133 void shutdown(void)
00134 {
00135 dc1394_camera_free(camera_);
00136 camera_ = NULL;
00137 }
00138
00142 bool trigger(void)
00143 {
00144 dc1394error_t err = dc1394_software_trigger_set_power(camera_, DC1394_ON);
00145 bool retval = (err == DC1394_SUCCESS);
00146 if (!retval)
00147 ROS_FATAL("camera does not provide software trigger");
00148 return retval;
00149 }
00150
00151 ros::NodeHandle node_;
00152 dc1394camera_t *camera_;
00153 };
00154
00156 int main(int argc, char **argv)
00157 {
00158 ros::init(argc, argv, "camera1394_trigger_node");
00159 signal(SIGSEGV, &sigsegv_handler);
00160
00161 TriggerNode trig;
00162
00163 if (!trig.setup())
00164 return 1;
00165
00166 if (!trig.spin())
00167 return 2;
00168
00169 return 0;
00170 }
camera1394
Author(s): Jack O'Quin, Ken Tossell, Patrick Beeson, Nate Koenig, Andrew Howard, Damien Douxchamps, Dan Dennedy
autogenerated on Thu Jun 6 2019 19:34:17