59 #include <sensor_msgs/CameraInfo.h>
61 #include <wfov_camera_msgs/WFOVImage.h>
62 #include <image_exposure_msgs/ExposureSequence.h>
67 #include <boost/thread.hpp>
69 #include <dynamic_reconfigure/server.h>
107 catch (
const std::runtime_error& e)
125 void paramCallback(
const spinnaker_camera_driver::SpinnakerConfig& config, uint32_t level)
136 wb_blue_ = config.white_balance_blue_ratio;
137 wb_red_ = config.white_balance_red_ratio;
140 binning_x_ = config.image_format_x_binning * config.image_format_x_decimation;
141 binning_y_ = config.image_format_y_binning * config.image_format_y_decimation;
147 if ((config.image_format_roi_width + config.image_format_roi_height) > 0 &&
167 catch (std::runtime_error& e)
169 NODELET_ERROR(
"Reconfigure Callback failed with error: %s", e.what());
265 pnh.
getParam(
"serial", serial_xmlrpc);
268 pnh.
param<
int>(
"serial", serial, 0);
272 std::string serial_str;
273 pnh.
param<std::string>(
"serial", serial_str,
"0");
274 std::istringstream(serial_str) >> serial;
282 std::string camera_serial_path;
283 pnh.
param<std::string>(
"camera_serial_path", camera_serial_path,
"");
287 while (serial == 0 && !camera_serial_path.empty())
310 std::string camera_info_url;
311 pnh.
param<std::string>(
"camera_info_url", camera_info_url,
"");
318 srv_ = std::make_shared<dynamic_reconfigure::Server<spinnaker_camera_driver::SpinnakerConfig> >(pnh);
319 dynamic_reconfigure::Server<spinnaker_camera_driver::SpinnakerConfig>::CallbackType
f =
322 srv_->setCallback(
f);
326 pnh.
param<
int>(
"queue_size", queue_size, 5);
329 std::stringstream cinfo_name;
330 cinfo_name << serial;
336 it_pub_ =
it_->advertiseCamera(
"image_raw", queue_size, cb, cb);
343 std::string device_type;
344 pnh.
param<std::string>(
"device_type", device_type,
"USB3");
345 pnh.
param<
double>(
"desired_freq", desired_freq, 30.0);
348 double freq_tolerance;
350 pnh.
param<
double>(
"freq_tolerance", freq_tolerance, 0.1);
352 pnh.
param<
int>(
"window_size", window_size, 30);
353 double min_acceptable;
355 pnh.
param<
double>(
"min_acceptable_delay", min_acceptable, 0.0);
356 double max_acceptable;
357 pnh.
param<
double>(
"max_acceptable_delay", max_acceptable, 0.2);
360 nh.
advertise<wfov_camera_msgs::WFOVImage>(
"image", queue_size, cb2, cb2),
372 nh.
advertise<diagnostic_msgs::DiagnosticArray>(
"/diagnostics", 1, diag_cb, diag_cb)));
376 diag_man->addDiagnostic(
"DeviceTemperature",
true, std::make_pair(0.0
f, 90.0
f), -10.0
f, 95.0
f);
377 diag_man->addDiagnostic(
"AcquisitionResultingFrameRate",
true, std::make_pair(10.0
f, 60.0
f), 5.0
f, 90.0
f);
378 diag_man->addDiagnostic(
"PowerSupplyVoltage",
true, std::make_pair(4.5
f, 5.2
f), 4.4
f, 5.3
f);
379 diag_man->addDiagnostic(
"PowerSupplyCurrent",
true, std::make_pair(0.4
f, 0.6
f), 0.3
f, 1.0
f);
380 diag_man->addDiagnostic<
int>(
"DeviceUptime");
381 if (device_type.compare(
"USB3") == 0 )
383 diag_man->addDiagnostic<
int>(
"U3VMessageChannelID");
396 NODELET_DEBUG_ONCE(
"Reading camera serial file from: %s", camera_serial_path.c_str());
398 std::ifstream serial_file(camera_serial_path.c_str());
399 std::stringstream buffer;
402 if (serial_file.is_open())
404 std::string serial_str((std::istreambuf_iterator<char>(serial_file)), std::istreambuf_iterator<char>());
406 buffer << std::hex << serial_str;
420 while (!boost::this_thread::interruption_requested())
448 State state = DISCONNECTED;
449 State previous_state =
NONE;
451 while (!boost::this_thread::interruption_requested())
453 bool state_changed = state != previous_state;
455 previous_state = state;
477 catch (std::runtime_error& e)
497 state = DISCONNECTED;
499 catch (std::runtime_error& e)
503 NODELET_ERROR(
"Failed to disconnect with error: %s", e.what());
532 catch (
const std::runtime_error& e)
546 catch (
const std::runtime_error& e)
564 NODELET_DEBUG(
"Attention: if nothing subscribes to the camera topic, the camera_info is not published "
565 "on the correspondent topic.");
568 catch (std::runtime_error& e)
582 wfov_camera_msgs::WFOVImagePtr wfov_image(
new wfov_camera_msgs::WFOVImage);
590 wfov_image->gain =
gain_;
591 wfov_image->white_balance_blue =
wb_blue_;
592 wfov_image->white_balance_red =
wb_red_;
597 wfov_image->header.stamp = time;
598 wfov_image->image.header.stamp = time;
601 ci_.reset(
new sensor_msgs::CameraInfo(
cinfo_->getCameraInfo()));
602 ci_->header.stamp = wfov_image->image.header.stamp;
603 ci_->header.frame_id = wfov_image->header.frame_id;
613 wfov_image->info = *
ci_;
616 pub_->publish(wfov_image);
621 sensor_msgs::ImagePtr image(
new sensor_msgs::Image(wfov_image->image));
630 catch (std::runtime_error& e)
652 msg.white_balance_blue,
msg.white_balance_red);
662 catch (std::runtime_error& e)
664 NODELET_ERROR(
"gainWBCallback failed with error: %s", e.what());
669 std::shared_ptr<dynamic_reconfigure::Server<spinnaker_camera_driver::SpinnakerConfig> >
srv_;
670 std::shared_ptr<image_transport::ImageTransport>
it_;
675 std::shared_ptr<camera_info_manager::CameraInfoManager>
cinfo_;
679 std::shared_ptr<diagnostic_updater::DiagnosedPublisher<wfov_camera_msgs::WFOVImage> >
pub_;
694 sensor_msgs::CameraInfoPtr
ci_;
724 spinnaker_camera_driver::SpinnakerConfig
config_;