src
nerian_stereo_nodelet.h
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
15
#include <
nodelet/nodelet.h
>
16
#include "
nerian_stereo_node_base.h
"
17
18
namespace
nerian_stereo
{
19
20
class
StereoNodelet:
public
StereoNodeBase,
public
nodelet::Nodelet
{
21
public
:
25
void
stereoIteration
(
const
ros::TimerEvent
&);
29
virtual
void
onInit
();
30
private
:
31
// The nodelet does not initialize its own node handles
32
inline
ros::NodeHandle
&
getNH
()
override
{
return
nodelet::Nodelet::getNodeHandle
(); }
33
inline
ros::NodeHandle
&
getPrivateNH
()
override
{
return
nodelet::Nodelet::getPrivateNodeHandle
(); }
34
ros::Timer
timer
;
35
};
36
37
}
// namespace
38
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
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
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
nerian_stereo::StereoNodelet::timer
ros::Timer timer
Definition:
nerian_stereo_nodelet.h:58
ros::TimerEvent
nerian_stereo::StereoNodelet::getPrivateNH
ros::NodeHandle & getPrivateNH() override
Definition:
nerian_stereo_nodelet.h:57
nodelet::Nodelet
nodelet.h
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
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
nerian_stereo_node_base.h
ros::Timer
ros::NodeHandle
nerian_stereo
Author(s): Nerian Vision Technologies
autogenerated on Wed Jan 24 2024 04:06:47