Public Member Functions | Protected Member Functions | Private Attributes | List of all members
usb_cam_controllers::PacketController Class Reference

#include <packet_controllers.hpp>

Inheritance diagram for usb_cam_controllers::PacketController:
Inheritance graph
[legend]

Public Member Functions

 PacketController ()
 
virtual ~PacketController ()
 
- Public Member Functions inherited from usb_cam_controllers::SimplePacketController
virtual bool init (usb_cam_hardware_interface::PacketInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
 
 SimplePacketController ()
 
virtual void starting (const ros::Time &time)
 
virtual void stopping (const ros::Time &time)
 
virtual void update (const ros::Time &time, const ros::Duration &period)
 
virtual ~SimplePacketController ()
 
- Public Member Functions inherited from controller_interface::Controller< usb_cam_hardware_interface::PacketInterface >
virtual bool init (T *, ros::NodeHandle &)
 
virtual bool init (T *, ros::NodeHandle &, ros::NodeHandle &)
 
- Public Member Functions inherited from controller_interface::ControllerBase
virtual void aborting (const ros::Time &)
 
virtual void aborting (const ros::Time &)
 
bool abortRequest (const ros::Time &time)
 
bool abortRequest (const ros::Time &time)
 
 ControllerBase ()=default
 
 ControllerBase (const ControllerBase &)=delete
 
 ControllerBase (ControllerBase &&)=delete
 
bool isAborted () const
 
bool isAborted () const
 
bool isInitialized () const
 
bool isInitialized () const
 
bool isRunning () const
 
bool isRunning () const
 
bool isStopped () const
 
bool isStopped () const
 
bool isWaiting () const
 
bool isWaiting () const
 
ControllerBaseoperator= (const ControllerBase &)=delete
 
ControllerBaseoperator= (ControllerBase &&)=delete
 
bool startRequest (const ros::Time &time)
 
bool startRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
virtual void waiting (const ros::Time &)
 
virtual void waiting (const ros::Time &)
 
bool waitRequest (const ros::Time &time)
 
bool waitRequest (const ros::Time &time)
 
virtual ~ControllerBase ()=default
 

Protected Member Functions

virtual bool initImpl (usb_cam_hardware_interface::PacketInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
 
virtual void startingImpl (const ros::Time &time)
 
virtual void stoppingImpl (const ros::Time &time)
 
virtual void updateImpl (const ros::Time &time, const ros::Duration &period)
 
- Protected Member Functions inherited from controller_interface::Controller< usb_cam_hardware_interface::PacketInterface >
std::string getHardwareInterfaceType () const
 
bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override
 

Private Attributes

std::string encoding_
 
int height_
 
image_transport::Publisher publisher_
 
int skip_cnt_
 
int skip_max_
 
int width_
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
enum  ControllerState {
  ControllerState::CONSTRUCTED, ControllerState::INITIALIZED, ControllerState::RUNNING, ControllerState::STOPPED,
  ControllerState::WAITING, ControllerState::ABORTED
}
 
- Public Attributes inherited from controller_interface::ControllerBase
ControllerState state_
 
- Protected Attributes inherited from usb_cam_controllers::SimplePacketController
usb_cam_hardware_interface::PacketHandle packet_iface_
 

Detailed Description

Definition at line 23 of file packet_controllers.hpp.

Constructor & Destructor Documentation

◆ PacketController()

usb_cam_controllers::PacketController::PacketController ( )
inline

Definition at line 25 of file packet_controllers.hpp.

◆ ~PacketController()

virtual usb_cam_controllers::PacketController::~PacketController ( )
inlinevirtual

Definition at line 27 of file packet_controllers.hpp.

Member Function Documentation

◆ initImpl()

virtual bool usb_cam_controllers::PacketController::initImpl ( usb_cam_hardware_interface::PacketInterface hw,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh 
)
inlineprotectedvirtual

◆ startingImpl()

virtual void usb_cam_controllers::PacketController::startingImpl ( const ros::Time time)
inlineprotectedvirtual

◆ stoppingImpl()

virtual void usb_cam_controllers::PacketController::stoppingImpl ( const ros::Time time)
inlineprotectedvirtual

◆ updateImpl()

virtual void usb_cam_controllers::PacketController::updateImpl ( const ros::Time time,
const ros::Duration period 
)
inlineprotectedvirtual

Member Data Documentation

◆ encoding_

std::string usb_cam_controllers::PacketController::encoding_
private

Definition at line 71 of file packet_controllers.hpp.

◆ height_

int usb_cam_controllers::PacketController::height_
private

Definition at line 72 of file packet_controllers.hpp.

◆ publisher_

image_transport::Publisher usb_cam_controllers::PacketController::publisher_
private

Definition at line 76 of file packet_controllers.hpp.

◆ skip_cnt_

int usb_cam_controllers::PacketController::skip_cnt_
private

Definition at line 75 of file packet_controllers.hpp.

◆ skip_max_

int usb_cam_controllers::PacketController::skip_max_
private

Definition at line 73 of file packet_controllers.hpp.

◆ width_

int usb_cam_controllers::PacketController::width_
private

Definition at line 72 of file packet_controllers.hpp.


The documentation for this class was generated from the following file:


usb_cam_controllers
Author(s):
autogenerated on Wed Mar 2 2022 01:11:39