Public Member Functions | Private Types | Private Attributes | List of all members
zivid_camera::CaptureSettingsController< ZividSettingsType, SettingsConfigType, SettingsAcquisitionConfigType > Class Template Reference

Controller that manages dynamic_reconfigure nodes for Settings and Settings2D More...

#include <capture_settings_controller.h>

Public Member Functions

 CaptureSettingsController (ros::NodeHandle &nh, Zivid::Camera &camera, const std::string &config_node_name, std::size_t num_acquisition_servers)
 
std::size_t numAcquisitionConfigServers () const
 
void setZividSettings (const ZividSettingsType &settings)
 
ZividSettingsType zividSettings () const
 
 ~CaptureSettingsController ()
 

Private Types

using SettingsAcquisitionConfigTypeDRServer = ConfigDRServer< SettingsAcquisitionConfigType, typename ZividSettingsType::Acquisition >
 
using SettingsConfigTypeDRServer = ConfigDRServer< SettingsConfigType, ZividSettingsType >
 

Private Attributes

std::vector< std::unique_ptr< SettingsAcquisitionConfigTypeDRServer > > acquisition_config_dr_servers_
 
std::string config_node_name_
 
std::unique_ptr< SettingsConfigTypeDRServergeneral_config_dr_server_
 

Detailed Description

template<typename ZividSettingsType, typename SettingsConfigType, typename SettingsAcquisitionConfigType>
class zivid_camera::CaptureSettingsController< ZividSettingsType, SettingsConfigType, SettingsAcquisitionConfigType >

Controller that manages dynamic_reconfigure nodes for Settings and Settings2D

This is a templated class that handles Zivid::Settings and Zivid::Settings2D configuration. Note that within the Zivid SDK Settings and Settings2D are similar in structure, but there are some differences in what kind of settings are provided.

This controller sets up the dynamic_reconfigure nodes "settings/", "settings/acquisition_0" and so on, handles callbacks and updates the internal config state. It also provides methods to convert from/to Zivid::Settings/Settings2D objects.

Definition at line 31 of file capture_settings_controller.h.

Member Typedef Documentation

template<typename ZividSettingsType , typename SettingsConfigType , typename SettingsAcquisitionConfigType >
using zivid_camera::CaptureSettingsController< ZividSettingsType, SettingsConfigType, SettingsAcquisitionConfigType >::SettingsAcquisitionConfigTypeDRServer = ConfigDRServer<SettingsAcquisitionConfigType, typename ZividSettingsType::Acquisition>
private

Definition at line 51 of file capture_settings_controller.h.

template<typename ZividSettingsType , typename SettingsConfigType , typename SettingsAcquisitionConfigType >
using zivid_camera::CaptureSettingsController< ZividSettingsType, SettingsConfigType, SettingsAcquisitionConfigType >::SettingsConfigTypeDRServer = ConfigDRServer<SettingsConfigType, ZividSettingsType>
private

Definition at line 49 of file capture_settings_controller.h.

Constructor & Destructor Documentation

template<typename ZividSettingsType , typename SettingsConfigType , typename SettingsAcquisitionConfigType >
zivid_camera::CaptureSettingsController< ZividSettingsType, SettingsConfigType, SettingsAcquisitionConfigType >::CaptureSettingsController ( ros::NodeHandle nh,
Zivid::Camera &  camera,
const std::string &  config_node_name,
std::size_t  num_acquisition_servers 
)

Definition at line 70 of file capture_settings_controller.cpp.

template<typename ZividSettingsType , typename SettingsConfigType , typename SettingsAcquisitionConfigType >
zivid_camera::CaptureSettingsController< ZividSettingsType, SettingsConfigType, SettingsAcquisitionConfigType >::~CaptureSettingsController ( )
default

Member Function Documentation

template<typename ZividSettingsType , typename SettingsConfigType , typename SettingsAcquisitionConfigType >
std::size_t zivid_camera::CaptureSettingsController< ZividSettingsType, SettingsConfigType, SettingsAcquisitionConfigType >::numAcquisitionConfigServers ( ) const

Definition at line 160 of file capture_settings_controller.cpp.

template<typename ZividSettingsType , typename SettingsConfigType , typename SettingsAcquisitionConfigType >
void zivid_camera::CaptureSettingsController< ZividSettingsType, SettingsConfigType, SettingsAcquisitionConfigType >::setZividSettings ( const ZividSettingsType &  settings)

Definition at line 112 of file capture_settings_controller.cpp.

template<typename ZividSettingsType , typename SettingsConfigType , typename SettingsAcquisitionConfigType >
ZividSettingsType zivid_camera::CaptureSettingsController< ZividSettingsType, SettingsConfigType, SettingsAcquisitionConfigType >::zividSettings ( ) const

Definition at line 93 of file capture_settings_controller.cpp.

Member Data Documentation

template<typename ZividSettingsType , typename SettingsConfigType , typename SettingsAcquisitionConfigType >
std::vector<std::unique_ptr<SettingsAcquisitionConfigTypeDRServer> > zivid_camera::CaptureSettingsController< ZividSettingsType, SettingsConfigType, SettingsAcquisitionConfigType >::acquisition_config_dr_servers_
private

Definition at line 54 of file capture_settings_controller.h.

template<typename ZividSettingsType , typename SettingsConfigType , typename SettingsAcquisitionConfigType >
std::string zivid_camera::CaptureSettingsController< ZividSettingsType, SettingsConfigType, SettingsAcquisitionConfigType >::config_node_name_
private

Definition at line 52 of file capture_settings_controller.h.

template<typename ZividSettingsType , typename SettingsConfigType , typename SettingsAcquisitionConfigType >
std::unique_ptr<SettingsConfigTypeDRServer> zivid_camera::CaptureSettingsController< ZividSettingsType, SettingsConfigType, SettingsAcquisitionConfigType >::general_config_dr_server_
private

Definition at line 53 of file capture_settings_controller.h.


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


zivid_camera
Author(s): Zivid
autogenerated on Sat Apr 17 2021 02:51:05