36 #include <dc1394/dc1394.h> 52 signal(SIGSEGV, SIG_DFL);
53 fprintf(stderr,
"Segmentation fault, stopping camera driver.\n");
54 ROS_FATAL(
"Segmentation fault, stopping camera.");
75 dc1394_t *dev = dc1394_new();
78 ROS_FATAL(
"Failed to initialize dc1394_context.");
83 dc1394camera_list_t *cameras;
84 int err = dc1394_camera_enumerate(dev, &cameras);
85 if (err != DC1394_SUCCESS)
87 ROS_FATAL(
"Could not get list of cameras");
90 if (cameras->num == 0)
98 << std::setw(16) << std::setfill(
'0') << std::hex
99 << cameras->ids[0].guid);
100 camera_ = dc1394_camera_new(dev, cameras->ids[0].guid);
103 ROS_FATAL(
"Failed to initialize camera.");
107 dc1394_camera_free_list(cameras);
144 dc1394error_t err = dc1394_software_trigger_set_power(
camera_, DC1394_ON);
145 bool retval = (err == DC1394_SUCCESS);
147 ROS_FATAL(
"camera does not provide software trigger");
156 int main(
int argc,
char **argv)
158 ros::init(argc, argv,
"camera1394_trigger_node");
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void sigsegv_handler(int sig)
#define ROS_INFO_STREAM(args)
ROSCPP_DECL void shutdown()
ROSCPP_DECL void spinOnce()
int main(int argc, char **argv)