nerian_stereo_nodelet.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2  * Copyright (c) 2022 Nerian Vision GmbH
3  *
4  * Permission is hereby granted, free of charge, to any person obtaining a copy
5  * of this software and associated documentation files (the "Software"), to deal
6  * in the Software without restriction, including without limitation the rights
7  * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
8  * copies of the Software, and to permit persons to whom the Software is
9  * furnished to do so, subject to the following conditions:
10  *
11  * The above copyright notice and this permission notice shall be included in
12  * all copies or substantial portions of the Software.
13  *******************************************************************************/
14 
16 #include "nerian_stereo_nodelet.h"
17 
18 namespace nerian_stereo {
19 
23 }
24 
25 void StereoNodelet::onInit() {
28  try {
30  } catch(...) {
31  ROS_ERROR("Handshake with parameter server failed; no dynamic parameters - please verify firmware version. Image transport is unaffected.");
32  }
33  StereoNodeBase::publishTransform(); // initial transform
35  // 2kHz timer for lower latency (stereoIteration will then block)
37 }
38 
39 } // namespace
40 
nerian_stereo::StereoNodeBase::prepareAsyncTransfer
void prepareAsyncTransfer()
Connects to the image service to request the stream of image sets.
Definition: nerian_stereo_node_base.cpp:196
nerian_stereo::StereoNodeBase::processDataChannels
void processDataChannels()
Definition: nerian_stereo_node_base.cpp:732
nerian_stereo::StereoNodeBase::init
void init()
Performs general initializations.
Definition: nerian_stereo_node_base.cpp:88
nerian_stereo::StereoNodeBase::publishTransform
void publishTransform()
Definition: nerian_stereo_node_base.cpp:782
nerian_stereo::StereoNodelet::onInit
virtual void onInit()
Nodelet initialization: performs ROS parameter/dynamic_reconfigure init, connects to image service,...
Definition: nerian_stereo_nodelet.cpp:37
nerian_stereo::StereoNodelet
Definition: nerian_stereo_nodelet.h:32
nerian_stereo::StereoNodeBase::processOneImageSet
void processOneImageSet()
Definition: nerian_stereo_node_base.cpp:202
nerian_stereo_nodelet.h
class_list_macros.h
nerian_stereo::StereoNodelet::timer
ros::Timer timer
Definition: nerian_stereo_nodelet.h:58
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
nerian_stereo::StereoNodeBase::initDynamicReconfigure
void initDynamicReconfigure()
Definition: nerian_stereo_node_base.cpp:56
ros::TimerEvent
nodelet::Nodelet
nerian_stereo::StereoNodeBase::initDataChannelService
void initDataChannelService()
Definition: nerian_stereo_node_base.cpp:192
nerian_stereo::StereoNodelet::stereoIteration
void stereoIteration(const ros::TimerEvent &)
Callback for the ros::Timer that replaces a processing loop in Nodelets; wraps processOneImageSet()
Definition: nerian_stereo_nodelet.cpp:32
ROS_ERROR
#define ROS_ERROR(...)
nerian_stereo
A driver node that receives data from Nerian stereo devices and forwards it to ROS.
Definition: nerian_stereo_node.cpp:17
nerian_stereo::StereoNodelet::getNH
ros::NodeHandle & getNH() override
Definition: nerian_stereo_nodelet.h:56
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration


nerian_stereo
Author(s): Nerian Vision Technologies
autogenerated on Wed Jan 24 2024 04:06:47