packet_interface.hpp
Go to the documentation of this file.
1 #ifndef USB_CAM_HARDWARE_INTERFACE_PACKET_INTERFACE
2 #define USB_CAM_HARDWARE_INTERFACE_PACKET_INTERFACE
3 
4 #include <string>
5 
7 #include <ros/time.h>
8 
10 
11 // requirement for a hardware handle
12 // - copyable to be mapped in HardwareResourceManager
13 // - has getName() to be used in HardwareResouceManager
14 // - has reference to data
15 class PacketHandle {
16 public:
17  PacketHandle() : name_(), stamp_(NULL), start_(NULL), length_(NULL) {}
18  PacketHandle(const std::string &name, const ros::Time *const stamp, const void **const start,
19  const std::size_t *const length)
20  : name_(name), stamp_(stamp), start_(start), length_(length) {}
21  virtual ~PacketHandle() {}
22 
23  std::string getName() const { return name_; }
24  ros::Time getStamp() const { return *stamp_; }
25  const void *getStart() const { return *start_; }
26  template < typename Byte > const Byte *getStartAs() const {
27  return reinterpret_cast< const Byte * >(*start_);
28  };
29  std::size_t getLength() const { return *length_; }
30 
31 private:
32  std::string name_;
33  const ros::Time *stamp_;
34  const void **start_;
35  const std::size_t *length_;
36 };
37 
39 
40 } // namespace usb_cam_hardware_interface
41 
42 #endif
usb_cam_hardware_interface::PacketHandle::PacketHandle
PacketHandle()
Definition: packet_interface.hpp:17
usb_cam_hardware_interface::PacketHandle::getStamp
ros::Time getStamp() const
Definition: packet_interface.hpp:24
usb_cam_hardware_interface::PacketHandle
Definition: packet_interface.hpp:15
time.h
usb_cam_hardware_interface::PacketHandle::length_
const std::size_t * length_
Definition: packet_interface.hpp:35
usb_cam_hardware_interface::PacketHandle::getStartAs
const Byte * getStartAs() const
Definition: packet_interface.hpp:26
usb_cam_hardware_interface::PacketHandle::~PacketHandle
virtual ~PacketHandle()
Definition: packet_interface.hpp:21
usb_cam_hardware_interface::PacketHandle::name_
std::string name_
Definition: packet_interface.hpp:32
usb_cam_hardware_interface::PacketHandle::getStart
const void * getStart() const
Definition: packet_interface.hpp:25
usb_cam_hardware_interface::PacketHandle::getLength
std::size_t getLength() const
Definition: packet_interface.hpp:29
usb_cam_hardware_interface::PacketInterface
Definition: packet_interface.hpp:38
start
ROSCPP_DECL void start()
usb_cam_hardware_interface::PacketHandle::start_
const void ** start_
Definition: packet_interface.hpp:34
ros::Time
usb_cam_hardware_interface
Definition: packet_interface.hpp:9
usb_cam_hardware_interface::PacketHandle::getName
std::string getName() const
Definition: packet_interface.hpp:23
usb_cam_hardware_interface::PacketHandle::PacketHandle
PacketHandle(const std::string &name, const ros::Time *const stamp, const void **const start, const std::size_t *const length)
Definition: packet_interface.hpp:18
usb_cam_hardware_interface::PacketHandle::stamp_
const ros::Time * stamp_
Definition: packet_interface.hpp:33
hardware_interface::HardwareResourceManager
hardware_resource_manager.h


usb_cam_hardware_interface
Author(s):
autogenerated on Wed Mar 2 2022 01:11:37