include
usb_cam_hardware
usb_cam_hardware_nodelet.hpp
Go to the documentation of this file.
1
#ifndef USB_CAM_HARDWARE_USB_CAM_HARDWARE_NODELET
2
#define USB_CAM_HARDWARE_USB_CAM_HARDWARE_NODELET
3
4
#include <
controller_manager/controller_manager.h
>
5
#include <
nodelet/nodelet.h
>
6
#include <
ros/duration.h
>
7
#include <
ros/exception.h
>
8
#include <
ros/node_handle.h
>
9
#include <
ros/time.h
>
10
#include <
ros/timer.h
>
11
#include <
usb_cam_hardware/usb_cam_hardware.hpp
>
12
13
#include <boost/make_shared.hpp>
14
#include <boost/shared_ptr.hpp>
15
16
namespace
usb_cam_hardware
{
17
18
class
USBCamHardwareNodelet
:
public
nodelet::Nodelet
{
19
public
:
20
USBCamHardwareNodelet
() {}
21
22
virtual
~USBCamHardwareNodelet
() {
23
update_timer_
.
stop
();
// stop updating the controllers and hardware first
24
controllers_
.reset();
// unload the controllers using the hardware
25
hardware_
.reset();
// finally close the hardware
26
}
27
28
private
:
29
virtual
void
onInit
() {
30
ros::NodeHandle
nh(
getMTNodeHandle
()), pnh(
getMTPrivateNodeHandle
());
31
32
hardware_
= boost::make_shared< USBCamHardware >();
33
const
ros::Duration
time_per_frame(
hardware_
->init(pnh));
34
if
(time_per_frame <=
ros::Duration
(0.)) {
35
ROS_ERROR
(
"Cannot init usb cam hardware"
);
36
throw
ros::Exception
(
"Cannot init usb cam hardware"
);
37
}
38
39
controllers_
= boost::make_shared< controller_manager::ControllerManager >(
hardware_
.get(), nh);
40
41
update_timer_
= nh.createTimer(time_per_frame, &
USBCamHardwareNodelet::update
,
this
);
42
43
last_
=
ros::Time::now
();
44
}
45
46
void
update
(
const
ros::TimerEvent
&event) {
47
const
ros::Time
now(
ros::Time::now
());
48
const
ros::Duration
period(now -
last_
);
49
hardware_
->read(now, period);
50
controllers_
->update(now, period);
51
hardware_
->write(now, period);
52
last_
= now;
53
}
54
55
private
:
56
boost::shared_ptr< USBCamHardware >
hardware_
;
57
boost::shared_ptr< controller_manager::ControllerManager >
controllers_
;
58
ros::Timer
update_timer_
;
59
60
ros::Time
last_
;
61
};
62
63
}
// namespace usb_cam_hardware
64
65
#endif
node_handle.h
boost::shared_ptr
usb_cam_hardware::USBCamHardwareNodelet::onInit
virtual void onInit()
Definition:
usb_cam_hardware_nodelet.hpp:29
time.h
ros::Timer::stop
void stop()
nodelet::Nodelet::getMTPrivateNodeHandle
ros::NodeHandle & getMTPrivateNodeHandle() const
ros::Exception
usb_cam_hardware::USBCamHardwareNodelet::controllers_
boost::shared_ptr< controller_manager::ControllerManager > controllers_
Definition:
usb_cam_hardware_nodelet.hpp:57
usb_cam_hardware::USBCamHardwareNodelet::~USBCamHardwareNodelet
virtual ~USBCamHardwareNodelet()
Definition:
usb_cam_hardware_nodelet.hpp:22
controller_manager.h
usb_cam_hardware.hpp
usb_cam_hardware::USBCamHardwareNodelet
Definition:
usb_cam_hardware_nodelet.hpp:18
duration.h
usb_cam_hardware::USBCamHardwareNodelet::last_
ros::Time last_
Definition:
usb_cam_hardware_nodelet.hpp:60
usb_cam_hardware::USBCamHardwareNodelet::USBCamHardwareNodelet
USBCamHardwareNodelet()
Definition:
usb_cam_hardware_nodelet.hpp:20
ros::TimerEvent
timer.h
usb_cam_hardware::USBCamHardwareNodelet::update_timer_
ros::Timer update_timer_
Definition:
usb_cam_hardware_nodelet.hpp:58
usb_cam_hardware::USBCamHardwareNodelet::hardware_
boost::shared_ptr< USBCamHardware > hardware_
Definition:
usb_cam_hardware_nodelet.hpp:56
nodelet::Nodelet
ros::Time
nodelet.h
ROS_ERROR
#define ROS_ERROR(...)
usb_cam_hardware::USBCamHardwareNodelet::update
void update(const ros::TimerEvent &event)
Definition:
usb_cam_hardware_nodelet.hpp:46
usb_cam_hardware
Definition:
usb_cam_hardware.hpp:23
ros::Duration
ros::Timer
ros::NodeHandle
exception.h
nodelet::Nodelet::getMTNodeHandle
ros::NodeHandle & getMTNodeHandle() const
ros::Time::now
static Time now()
usb_cam_hardware
Author(s):
autogenerated on Wed Mar 2 2022 01:11:40