38 : nh_(nh), nhp_(nhp), it_(nh), left_cam_(
"left"), right_cam_(
"right") {
76 double min_freq = 2.0;
77 double max_freq = 20.0;
79 double min_stamp = 0.001;
80 double max_stamp = 1.0;
100 sensor_msgs::Image img;
104 lci.header.stamp = ros_time;
105 img.header.stamp = ros_time;
106 img.header.frame_id = lci.header.frame_id;
130 r_img.header.stamp = ros_time;
131 lci.header.stamp = ros_time;
132 rci.header.stamp = ros_time;
150 ROS_WARN_STREAM(
"Function frameToImage returned 0. No image published.");
156 std_msgs::Float64
msg;
167 sensor_msgs::Image img;
171 rci.header.stamp = ros_time;
172 img.header.stamp = ros_time;
173 img.header.frame_id = rci.header.frame_id;
199 l_img.header.stamp = ros_time;
200 lci.header.stamp = ros_time;
201 rci.header.stamp = ros_time;
219 ROS_WARN_STREAM(
"Function frameToImage returned 0. No image published.");
225 std_msgs::Float64
msg;
255 Config left_config, right_config;
256 copyConfig(newconfig, left_config, right_config);
260 }
catch (
const std::exception& e) {
261 ROS_ERROR_STREAM(
"Error reconfiguring avt_vimba_camera node : " << e.what());
267 lc.frame_id = sc.left_frame_id;
268 lc.trig_timestamp_topic = sc.left_trig_timestamp_topic;
269 lc.acquisition_mode = sc.left_acquisition_mode;
270 lc.acquisition_rate = sc.left_acquisition_rate;
271 lc.trigger_source = sc.left_trigger_source;
272 lc.trigger_mode = sc.left_trigger_mode;
273 lc.trigger_selector = sc.left_trigger_selector;
274 lc.trigger_activation = sc.left_trigger_activation;
275 lc.trigger_delay = sc.left_trigger_delay;
276 lc.exposure = sc.exposure;
277 lc.exposure_auto = sc.exposure_auto;
278 lc.exposure_auto_alg = sc.exposure_auto_alg;
279 lc.exposure_auto_tol = sc.exposure_auto_tol;
280 lc.exposure_auto_max = sc.exposure_auto_max;
281 lc.exposure_auto_min = sc.exposure_auto_min;
282 lc.exposure_auto_outliers = sc.exposure_auto_outliers;
283 lc.exposure_auto_rate = sc.exposure_auto_rate;
284 lc.exposure_auto_target = sc.exposure_auto_target;
286 lc.gain_auto = sc.gain_auto;
287 lc.gain_auto_tol = sc.gain_auto_tol;
288 lc.gain_auto_max = sc.gain_auto_max;
289 lc.gain_auto_min = sc.gain_auto_min;
290 lc.gain_auto_outliers = sc.gain_auto_outliers;
291 lc.gain_auto_rate = sc.gain_auto_rate;
292 lc.gain_auto_target = sc.gain_auto_target;
293 lc.balance_ratio_abs = sc.balance_ratio_abs;
294 lc.balance_ratio_selector = sc.balance_ratio_selector;
295 lc.whitebalance_auto = sc.whitebalance_auto;
296 lc.whitebalance_auto_tol = sc.whitebalance_auto_tol;
297 lc.whitebalance_auto_rate = sc.whitebalance_auto_rate;
298 lc.binning_x = sc.binning_x;
299 lc.binning_y = sc.binning_y;
300 lc.decimation_x = sc.decimation_x;
301 lc.decimation_y = sc.decimation_y;
303 lc.height = sc.height;
304 lc.roi_width = sc.roi_width;
305 lc.roi_height = sc.roi_height;
306 lc.roi_offset_x = sc.roi_offset_x;
307 lc.roi_offset_y = sc.roi_offset_y;
308 lc.pixel_format = sc.pixel_format;
309 lc.stream_bytes_per_second = sc.stream_bytes_per_second;
310 lc.ptp_mode = sc.left_ptp_mode;
311 lc.sync_in_selector = sc.left_sync_in_selector;
312 lc.sync_out_polarity = sc.left_sync_out_polarity;
313 lc.sync_out_selector = sc.left_sync_out_selector;
314 lc.sync_out_source = sc.left_sync_out_source;
316 rc.frame_id = sc.right_frame_id;
317 rc.trig_timestamp_topic = sc.right_trig_timestamp_topic;
318 rc.acquisition_mode = sc.right_acquisition_mode;
319 rc.acquisition_rate = sc.right_acquisition_rate;
320 rc.trigger_source = sc.right_trigger_source;
321 rc.trigger_mode = sc.right_trigger_mode;
322 rc.trigger_selector = sc.right_trigger_selector;
323 rc.trigger_activation = sc.right_trigger_activation;
324 rc.trigger_delay = sc.right_trigger_delay;
325 rc.exposure = sc.exposure;
326 rc.exposure_auto = sc.exposure_auto;
327 rc.exposure_auto_alg = sc.exposure_auto_alg;
328 rc.exposure_auto_tol = sc.exposure_auto_tol;
329 rc.exposure_auto_max = sc.exposure_auto_max;
330 rc.exposure_auto_min = sc.exposure_auto_min;
331 rc.exposure_auto_outliers = sc.exposure_auto_outliers;
332 rc.exposure_auto_rate = sc.exposure_auto_rate;
333 rc.exposure_auto_target = sc.exposure_auto_target;
335 rc.gain_auto = sc.gain_auto;
336 rc.gain_auto_tol = sc.gain_auto_tol;
337 rc.gain_auto_max = sc.gain_auto_max;
338 rc.gain_auto_min = sc.gain_auto_min;
339 rc.gain_auto_outliers = sc.gain_auto_outliers;
340 rc.gain_auto_rate = sc.gain_auto_rate;
341 rc.gain_auto_target = sc.gain_auto_target;
342 rc.balance_ratio_abs = sc.balance_ratio_abs;
343 rc.balance_ratio_selector = sc.balance_ratio_selector;
344 rc.whitebalance_auto = sc.whitebalance_auto;
345 rc.whitebalance_auto_tol = sc.whitebalance_auto_tol;
346 rc.whitebalance_auto_rate = sc.whitebalance_auto_rate;
347 rc.binning_x = sc.binning_x;
348 rc.binning_y = sc.binning_y;
349 rc.decimation_x = sc.decimation_x;
350 rc.decimation_y = sc.decimation_y;
352 rc.height = sc.height;
353 rc.roi_width = sc.roi_width;
354 rc.roi_height = sc.roi_height;
355 rc.roi_offset_x = sc.roi_offset_x;
356 rc.roi_offset_y = sc.roi_offset_y;
357 rc.pixel_format = sc.pixel_format;
358 rc.stream_bytes_per_second = sc.stream_bytes_per_second;
359 rc.ptp_mode = sc.right_ptp_mode;
360 rc.sync_in_selector = sc.right_sync_in_selector;
361 rc.sync_out_polarity = sc.right_sync_out_polarity;
362 rc.sync_out_selector = sc.right_sync_out_selector;
363 rc.sync_out_source = sc.right_sync_out_source;
368 sensor_msgs::CameraInfo left_ci =
left_info_man_->getCameraInfo();
372 left_ci.header.frame_id = config.left_frame_id;
373 right_ci.header.frame_id = config.right_frame_id;
376 int binning_or_decimation_x = std::max(config.binning_x, config.decimation_x);
377 int binning_or_decimation_y = std::max(config.binning_y, config.decimation_y);
379 left_ci.height = config.height/binning_or_decimation_x;
380 left_ci.width = config.width/binning_or_decimation_y;
381 left_ci.binning_x = 1;
382 left_ci.binning_y = 1;
384 right_ci.height = config.height/binning_or_decimation_x;
385 right_ci.width = config.width/binning_or_decimation_y;
386 right_ci.binning_x = 1;
387 right_ci.binning_y = 1;
390 left_ci.roi.x_offset = config.roi_offset_x/binning_or_decimation_x;
391 left_ci.roi.y_offset = config.roi_offset_y/binning_or_decimation_y;
392 left_ci.roi.height = config.roi_height/binning_or_decimation_x;
393 left_ci.roi.width = config.roi_width/binning_or_decimation_y;
395 right_ci.roi.x_offset = config.roi_offset_x/binning_or_decimation_x;
396 right_ci.roi.y_offset = config.roi_offset_y/binning_or_decimation_y;
397 right_ci.roi.height = config.roi_height/binning_or_decimation_x;
398 right_ci.roi.width = config.roi_width/binning_or_decimation_y;
400 std::string left_camera_info_url, right_camera_info_url;
411 ROS_WARN_STREAM(
"Camera info URL not valid: " << left_camera_info_url);
421 ROS_WARN_STREAM(
"Camera info URL not valid: " << right_camera_info_url);
425 bool lRoiMatchesCalibration = (left_ci.height == config.roi_height
426 && left_ci.width == config.roi_width);
427 bool lResolutionMatchesCalibration = (left_ci.width == config.width
428 && left_ci.height == config.height);
430 left_ci.roi.do_rectify = lRoiMatchesCalibration || lResolutionMatchesCalibration;
432 bool rRoiMatchesCalibration = (right_ci.height == config.roi_height
433 && right_ci.width == config.roi_width);
434 bool rResolutionMatchesCalibration = (right_ci.width == config.width
435 && right_ci.height == config.height);
437 right_ci.roi.do_rectify = rRoiMatchesCalibration || rResolutionMatchesCalibration;
diagnostic_updater::Updater updater_
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
NetPointer< Frame, AVT::VmbAPINET::Frame > FramePtr
std::string right_camera_info_url_
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< camera_info_manager::CameraInfoManager > left_info_man_
bool getParamCached(const std::string &key, std::string &s) const
std::string left_camera_info_url_
uint32_t getNumSubscribers() const
void setHardwareID(const std::string &hwid)
ReconfigureServer reconfigure_server_
ros::Publisher pub_left_temp_
bool resetTimestamp(void)
image_transport::ImageTransport it_
std::vector< sensor_msgs::Image > r_imgs_buffer_
void setCallback(frameCallbackFunc callback=&avt_vimba_camera::AvtVimbaCamera::defaultFrameCallback)
void leftFrameCallback(const FramePtr &vimba_frame_ptr)
bool frameToImage(const FramePtr vimba_frame_ptr, sensor_msgs::Image &image)
boost::shared_ptr< camera_info_manager::CameraInfoManager > right_info_man_
void updateConfig(Config &config)
avt_vimba_camera::AvtVimbaCameraStereoConfig StereoConfig
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
StereoCamera(ros::NodeHandle nh, ros::NodeHandle nhp)
void configure(StereoConfig &newconfig, uint32_t level)
std::vector< sensor_msgs::Image > l_imgs_buffer_
void copyConfig(StereoConfig &sc, Config &lc, Config &rc)
void start(std::string ip_str, std::string guid_str, bool debug_prints=true)
image_transport::CameraPublisher left_pub_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double getDeviceTemp(void)
#define ROS_WARN_STREAM(args)
uint32_t getNumSubscribers() const
void rightFrameCallback(const FramePtr &vimba_frame_ptr)
void broadcast(int lvl, const std::string msg)
#define ROS_ERROR_STREAM(args)
avt_vimba_camera::AvtVimbaCameraConfig Config
ros::Publisher pub_right_temp_
image_transport::CameraPublisher right_pub_
AvtVimbaCamera right_cam_
void updateCameraInfo(const StereoConfig &config)