Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
l3cam_ros::RgbConfiguration Class Reference
Inheritance diagram for l3cam_ros::RgbConfiguration:
Inheritance graph
[legend]

Public Member Functions

 RgbConfiguration ()
 
void setDynamicReconfigure ()
 
void spin ()
 
- Public Member Functions inherited from ros::NodeHandle
Publisher advertise (AdvertiseOptions &ops)
 
Publisher advertise (const std::string &topic, uint32_t queue_size, bool latch=false)
 
Publisher advertise (const std::string &topic, uint32_t queue_size, const SubscriberStatusCallback &connect_cb, const SubscriberStatusCallback &disconnect_cb=SubscriberStatusCallback(), const VoidConstPtr &tracked_object=VoidConstPtr(), bool latch=false)
 
ServiceServer advertiseService (AdvertiseServiceOptions &ops)
 
ServiceServer advertiseService (const std::string &service, bool(*srv_func)(MReq &, MRes &))
 
ServiceServer advertiseService (const std::string &service, bool(*srv_func)(ServiceEvent< MReq, MRes > &))
 
ServiceServer advertiseService (const std::string &service, bool(T::*srv_func)(MReq &, MRes &), const boost::shared_ptr< T > &obj)
 
ServiceServer advertiseService (const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
 
ServiceServer advertiseService (const std::string &service, bool(T::*srv_func)(ServiceEvent< MReq, MRes > &), const boost::shared_ptr< T > &obj)
 
ServiceServer advertiseService (const std::string &service, bool(T::*srv_func)(ServiceEvent< MReq, MRes > &), T *obj)
 
ServiceServer advertiseService (const std::string &service, const boost::function< bool(MReq &, MRes &)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr())
 
ServiceServer advertiseService (const std::string &service, const boost::function< bool(S &)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr())
 
SteadyTimer createSteadyTimer (SteadyTimerOptions &ops) const
 
SteadyTimer createSteadyTimer (WallDuration period, const SteadyTimerCallback &callback, bool oneshot=false, bool autostart=true) const
 
SteadyTimer createSteadyTimer (WallDuration period, void(T::*callback)(const SteadyTimerEvent &), const boost::shared_ptr< T > &obj, bool oneshot=false, bool autostart=true) const
 
SteadyTimer createSteadyTimer (WallDuration period, void(T::*callback)(const SteadyTimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
 
Timer createTimer (Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
 
Timer createTimer (Duration period, void(T::*callback)(const TimerEvent &) const, T *obj, bool oneshot=false, bool autostart=true) const
 
Timer createTimer (Duration period, void(T::*callback)(const TimerEvent &), const boost::shared_ptr< T > &obj, bool oneshot=false, bool autostart=true) const
 
Timer createTimer (Duration period, void(T::*callback)(const TimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
 
Timer createTimer (Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
 
Timer createTimer (TimerOptions &ops) const
 
WallTimer createWallTimer (WallDuration period, const WallTimerCallback &callback, bool oneshot=false, bool autostart=true) const
 
WallTimer createWallTimer (WallDuration period, void(T::*callback)(const WallTimerEvent &), const boost::shared_ptr< T > &obj, bool oneshot=false, bool autostart=true) const
 
WallTimer createWallTimer (WallDuration period, void(T::*callback)(const WallTimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
 
WallTimer createWallTimer (WallTimerOptions &ops) const
 
bool deleteParam (const std::string &key) const
 
CallbackQueueInterfacegetCallbackQueue () const
 
const std::string & getNamespace () const
 
bool getParam (const std::string &key, bool &b) const
 
bool getParam (const std::string &key, double &d) const
 
bool getParam (const std::string &key, float &f) const
 
bool getParam (const std::string &key, int &i) const
 
bool getParam (const std::string &key, std::map< std::string, bool > &map) const
 
bool getParam (const std::string &key, std::map< std::string, double > &map) const
 
bool getParam (const std::string &key, std::map< std::string, float > &map) const
 
bool getParam (const std::string &key, std::map< std::string, int > &map) const
 
bool getParam (const std::string &key, std::map< std::string, std::string > &map) const
 
bool getParam (const std::string &key, std::string &s) const
 
bool getParam (const std::string &key, std::vector< bool > &vec) const
 
bool getParam (const std::string &key, std::vector< double > &vec) const
 
bool getParam (const std::string &key, std::vector< float > &vec) const
 
bool getParam (const std::string &key, std::vector< int > &vec) const
 
bool getParam (const std::string &key, std::vector< std::string > &vec) const
 
bool getParam (const std::string &key, XmlRpc::XmlRpcValue &v) const
 
bool getParamCached (const std::string &key, bool &b) const
 
bool getParamCached (const std::string &key, double &d) const
 
bool getParamCached (const std::string &key, float &f) const
 
bool getParamCached (const std::string &key, int &i) const
 
bool getParamCached (const std::string &key, std::map< std::string, bool > &map) const
 
bool getParamCached (const std::string &key, std::map< std::string, double > &map) const
 
bool getParamCached (const std::string &key, std::map< std::string, float > &map) const
 
bool getParamCached (const std::string &key, std::map< std::string, int > &map) const
 
bool getParamCached (const std::string &key, std::map< std::string, std::string > &map) const
 
bool getParamCached (const std::string &key, std::string &s) const
 
bool getParamCached (const std::string &key, std::vector< bool > &vec) const
 
bool getParamCached (const std::string &key, std::vector< double > &vec) const
 
bool getParamCached (const std::string &key, std::vector< float > &vec) const
 
bool getParamCached (const std::string &key, std::vector< int > &vec) const
 
bool getParamCached (const std::string &key, std::vector< std::string > &vec) const
 
bool getParamCached (const std::string &key, XmlRpc::XmlRpcValue &v) const
 
bool getParamNames (std::vector< std::string > &keys) const
 
const std::string & getUnresolvedNamespace () const
 
bool hasParam (const std::string &key) const
 
 NodeHandle (const NodeHandle &parent, const std::string &ns)
 
 NodeHandle (const NodeHandle &parent, const std::string &ns, const M_string &remappings)
 
 NodeHandle (const NodeHandle &rhs)
 
 NodeHandle (const std::string &ns=std::string(), const M_string &remappings=M_string())
 
bool ok () const
 
NodeHandleoperator= (const NodeHandle &rhs)
 
param (const std::string &param_name, const T &default_val) const
 
bool param (const std::string &param_name, T &param_val, const T &default_val) const
 
std::string resolveName (const std::string &name, bool remap=true) const
 
bool searchParam (const std::string &key, std::string &result) const
 
ServiceClient serviceClient (const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
 
ServiceClient serviceClient (const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
 
ServiceClient serviceClient (ServiceClientOptions &ops)
 
void setCallbackQueue (CallbackQueueInterface *queue)
 
void setParam (const std::string &key, bool b) const
 
void setParam (const std::string &key, const char *s) const
 
void setParam (const std::string &key, const std::map< std::string, bool > &map) const
 
void setParam (const std::string &key, const std::map< std::string, double > &map) const
 
void setParam (const std::string &key, const std::map< std::string, float > &map) const
 
void setParam (const std::string &key, const std::map< std::string, int > &map) const
 
void setParam (const std::string &key, const std::map< std::string, std::string > &map) const
 
void setParam (const std::string &key, const std::string &s) const
 
void setParam (const std::string &key, const std::vector< bool > &vec) const
 
void setParam (const std::string &key, const std::vector< double > &vec) const
 
void setParam (const std::string &key, const std::vector< float > &vec) const
 
void setParam (const std::string &key, const std::vector< int > &vec) const
 
void setParam (const std::string &key, const std::vector< std::string > &vec) const
 
void setParam (const std::string &key, const XmlRpc::XmlRpcValue &v) const
 
void setParam (const std::string &key, double d) const
 
void setParam (const std::string &key, int i) const
 
void shutdown ()
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, const boost::function< void(const boost::shared_ptr< M const > &)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(*fp)(const boost::shared_ptr< M const > &), const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(*fp)(M), const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &) const, const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &) const, T *obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &), T *obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(M) const, const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(M) const, T *obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(M), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (SubscribeOptions &ops)
 
 ~NodeHandle ()
 

Public Attributes

ros::ServiceClient client_get_sensors_
 
l3cam_ros::GetSensorsAvailable srv_get_sensors_
 
int timeout_secs_
 

Private Member Functions

int callRgbAutoExposureTime (l3cam_ros::RgbConfig &config)
 
int callRgbAutoWhiteBalance (l3cam_ros::RgbConfig &config)
 
int callRgbBrightness (l3cam_ros::RgbConfig &config)
 
int callRgbContrast (l3cam_ros::RgbConfig &config)
 
int callRgbExposureTime (l3cam_ros::RgbConfig &config)
 
int callRgbGain (l3cam_ros::RgbConfig &config)
 
int callRgbGamma (l3cam_ros::RgbConfig &config)
 
int callRgbRtspPipeline (l3cam_ros::RgbConfig &config)
 
int callRgbSaturation (l3cam_ros::RgbConfig &config)
 
int callRgbSharpness (l3cam_ros::RgbConfig &config)
 
int callRgbStreamingProtocol (l3cam_ros::RgbConfig &config)
 
int callRgbWhiteBalance (l3cam_ros::RgbConfig &config)
 
void configureDefault (l3cam_ros::RgbConfig &config)
 
void loadDefaultParams ()
 
template<typename T >
void loadParam (const std::string &param_name, T &param_var, const T &default_val)
 
void parametersCallback (l3cam_ros::RgbConfig &config, uint32_t level)
 
bool sensorDisconnectedCallback (l3cam_ros::SensorDisconnected::Request &req, l3cam_ros::SensorDisconnected::Response &res)
 

Private Attributes

ros::ServiceClient client_brightness_
 
ros::ServiceClient client_change_streaming_protocol_
 
ros::ServiceClient client_contrast_
 
ros::ServiceClient client_enable_auto_exposure_time_
 
ros::ServiceClient client_enable_auto_white_balance_
 
ros::ServiceClient client_exposure_time_
 
ros::ServiceClient client_gain_
 
ros::ServiceClient client_gamma_
 
ros::ServiceClient client_get_rtsp_pipeline_
 
ros::ServiceClient client_saturation_
 
ros::ServiceClient client_sharpness_
 
ros::ServiceClient client_white_balance_
 
bool m_default_configured
 
bool m_shutdown_requested
 
bool rgb_auto_exposure_time_
 
bool rgb_auto_white_balance_
 
int rgb_brightness_
 
int rgb_contrast_
 
int rgb_exposure_time_
 
int rgb_gain_
 
int rgb_gamma_
 
std::string rgb_rtsp_pipeline_
 
int rgb_saturation_
 
int rgb_sharpness_
 
int rgb_streaming_protocol_
 
int rgb_white_balance_
 
dynamic_reconfigure::Server< l3cam_ros::RgbConfig > * server_
 
l3cam_ros::ChangeRgbCameraBrightness srv_brightness_
 
l3cam_ros::ChangeStreamingProtocol srv_change_streaming_protocol_
 
l3cam_ros::ChangeRgbCameraContrast srv_contrast_
 
l3cam_ros::EnableRgbCameraAutoExposureTime srv_enable_auto_exposure_time_
 
l3cam_ros::EnableRgbCameraAutoWhiteBalance srv_enable_auto_white_balance_
 
l3cam_ros::ChangeRgbCameraExposureTime srv_exposure_time_
 
l3cam_ros::ChangeRgbCameraGain srv_gain_
 
l3cam_ros::ChangeRgbCameraGamma srv_gamma_
 
l3cam_ros::GetRtspPipeline srv_get_rtsp_pipeline_
 
l3cam_ros::ChangeRgbCameraSaturation srv_saturation_
 
ros::ServiceServer srv_sensor_disconnected_
 
l3cam_ros::ChangeRgbCameraSharpness srv_sharpness_
 
l3cam_ros::ChangeRgbCameraWhiteBalance srv_white_balance_
 

Detailed Description

Definition at line 58 of file rgb_configuration.cpp.

Constructor & Destructor Documentation

◆ RgbConfiguration()

l3cam_ros::RgbConfiguration::RgbConfiguration ( )
inlineexplicit

Definition at line 61 of file rgb_configuration.cpp.

Member Function Documentation

◆ callRgbAutoExposureTime()

int l3cam_ros::RgbConfiguration::callRgbAutoExposureTime ( l3cam_ros::RgbConfig &  config)
inlineprivate

Definition at line 570 of file rgb_configuration.cpp.

◆ callRgbAutoWhiteBalance()

int l3cam_ros::RgbConfiguration::callRgbAutoWhiteBalance ( l3cam_ros::RgbConfig &  config)
inlineprivate

Definition at line 504 of file rgb_configuration.cpp.

◆ callRgbBrightness()

int l3cam_ros::RgbConfiguration::callRgbBrightness ( l3cam_ros::RgbConfig &  config)
inlineprivate

Definition at line 330 of file rgb_configuration.cpp.

◆ callRgbContrast()

int l3cam_ros::RgbConfiguration::callRgbContrast ( l3cam_ros::RgbConfig &  config)
inlineprivate

Definition at line 359 of file rgb_configuration.cpp.

◆ callRgbExposureTime()

int l3cam_ros::RgbConfiguration::callRgbExposureTime ( l3cam_ros::RgbConfig &  config)
inlineprivate

Definition at line 599 of file rgb_configuration.cpp.

◆ callRgbGain()

int l3cam_ros::RgbConfiguration::callRgbGain ( l3cam_ros::RgbConfig &  config)
inlineprivate

Definition at line 475 of file rgb_configuration.cpp.

◆ callRgbGamma()

int l3cam_ros::RgbConfiguration::callRgbGamma ( l3cam_ros::RgbConfig &  config)
inlineprivate

Definition at line 446 of file rgb_configuration.cpp.

◆ callRgbRtspPipeline()

int l3cam_ros::RgbConfiguration::callRgbRtspPipeline ( l3cam_ros::RgbConfig &  config)
inlineprivate

Definition at line 666 of file rgb_configuration.cpp.

◆ callRgbSaturation()

int l3cam_ros::RgbConfiguration::callRgbSaturation ( l3cam_ros::RgbConfig &  config)
inlineprivate

Definition at line 388 of file rgb_configuration.cpp.

◆ callRgbSharpness()

int l3cam_ros::RgbConfiguration::callRgbSharpness ( l3cam_ros::RgbConfig &  config)
inlineprivate

Definition at line 417 of file rgb_configuration.cpp.

◆ callRgbStreamingProtocol()

int l3cam_ros::RgbConfiguration::callRgbStreamingProtocol ( l3cam_ros::RgbConfig &  config)
inlineprivate

Definition at line 636 of file rgb_configuration.cpp.

◆ callRgbWhiteBalance()

int l3cam_ros::RgbConfiguration::callRgbWhiteBalance ( l3cam_ros::RgbConfig &  config)
inlineprivate

Definition at line 533 of file rgb_configuration.cpp.

◆ configureDefault()

void l3cam_ros::RgbConfiguration::configureDefault ( l3cam_ros::RgbConfig &  config)
inlineprivate

Definition at line 147 of file rgb_configuration.cpp.

◆ loadDefaultParams()

void l3cam_ros::RgbConfiguration::loadDefaultParams ( )
inlineprivate

Definition at line 130 of file rgb_configuration.cpp.

◆ loadParam()

template<typename T >
void l3cam_ros::RgbConfiguration::loadParam ( const std::string &  param_name,
T &  param_var,
const T &  default_val 
)
inlineprivate

Definition at line 112 of file rgb_configuration.cpp.

◆ parametersCallback()

void l3cam_ros::RgbConfiguration::parametersCallback ( l3cam_ros::RgbConfig &  config,
uint32_t  level 
)
inlineprivate

Definition at line 271 of file rgb_configuration.cpp.

◆ sensorDisconnectedCallback()

bool l3cam_ros::RgbConfiguration::sensorDisconnectedCallback ( l3cam_ros::SensorDisconnected::Request &  req,
l3cam_ros::SensorDisconnected::Response &  res 
)
inlineprivate

Definition at line 675 of file rgb_configuration.cpp.

◆ setDynamicReconfigure()

void l3cam_ros::RgbConfiguration::setDynamicReconfigure ( )
inline

Definition at line 86 of file rgb_configuration.cpp.

◆ spin()

void l3cam_ros::RgbConfiguration::spin ( )
inline

Definition at line 94 of file rgb_configuration.cpp.

Member Data Documentation

◆ client_brightness_

ros::ServiceClient l3cam_ros::RgbConfiguration::client_brightness_
private

Definition at line 693 of file rgb_configuration.cpp.

◆ client_change_streaming_protocol_

ros::ServiceClient l3cam_ros::RgbConfiguration::client_change_streaming_protocol_
private

Definition at line 713 of file rgb_configuration.cpp.

◆ client_contrast_

ros::ServiceClient l3cam_ros::RgbConfiguration::client_contrast_
private

Definition at line 695 of file rgb_configuration.cpp.

◆ client_enable_auto_exposure_time_

ros::ServiceClient l3cam_ros::RgbConfiguration::client_enable_auto_exposure_time_
private

Definition at line 709 of file rgb_configuration.cpp.

◆ client_enable_auto_white_balance_

ros::ServiceClient l3cam_ros::RgbConfiguration::client_enable_auto_white_balance_
private

Definition at line 705 of file rgb_configuration.cpp.

◆ client_exposure_time_

ros::ServiceClient l3cam_ros::RgbConfiguration::client_exposure_time_
private

Definition at line 711 of file rgb_configuration.cpp.

◆ client_gain_

ros::ServiceClient l3cam_ros::RgbConfiguration::client_gain_
private

Definition at line 703 of file rgb_configuration.cpp.

◆ client_gamma_

ros::ServiceClient l3cam_ros::RgbConfiguration::client_gamma_
private

Definition at line 701 of file rgb_configuration.cpp.

◆ client_get_rtsp_pipeline_

ros::ServiceClient l3cam_ros::RgbConfiguration::client_get_rtsp_pipeline_
private

Definition at line 715 of file rgb_configuration.cpp.

◆ client_get_sensors_

ros::ServiceClient l3cam_ros::RgbConfiguration::client_get_sensors_

Definition at line 105 of file rgb_configuration.cpp.

◆ client_saturation_

ros::ServiceClient l3cam_ros::RgbConfiguration::client_saturation_
private

Definition at line 697 of file rgb_configuration.cpp.

◆ client_sharpness_

ros::ServiceClient l3cam_ros::RgbConfiguration::client_sharpness_
private

Definition at line 699 of file rgb_configuration.cpp.

◆ client_white_balance_

ros::ServiceClient l3cam_ros::RgbConfiguration::client_white_balance_
private

Definition at line 707 of file rgb_configuration.cpp.

◆ m_default_configured

bool l3cam_ros::RgbConfiguration::m_default_configured
private

Definition at line 733 of file rgb_configuration.cpp.

◆ m_shutdown_requested

bool l3cam_ros::RgbConfiguration::m_shutdown_requested
private

Definition at line 734 of file rgb_configuration.cpp.

◆ rgb_auto_exposure_time_

bool l3cam_ros::RgbConfiguration::rgb_auto_exposure_time_
private

Definition at line 728 of file rgb_configuration.cpp.

◆ rgb_auto_white_balance_

bool l3cam_ros::RgbConfiguration::rgb_auto_white_balance_
private

Definition at line 726 of file rgb_configuration.cpp.

◆ rgb_brightness_

int l3cam_ros::RgbConfiguration::rgb_brightness_
private

Definition at line 720 of file rgb_configuration.cpp.

◆ rgb_contrast_

int l3cam_ros::RgbConfiguration::rgb_contrast_
private

Definition at line 721 of file rgb_configuration.cpp.

◆ rgb_exposure_time_

int l3cam_ros::RgbConfiguration::rgb_exposure_time_
private

Definition at line 729 of file rgb_configuration.cpp.

◆ rgb_gain_

int l3cam_ros::RgbConfiguration::rgb_gain_
private

Definition at line 725 of file rgb_configuration.cpp.

◆ rgb_gamma_

int l3cam_ros::RgbConfiguration::rgb_gamma_
private

Definition at line 724 of file rgb_configuration.cpp.

◆ rgb_rtsp_pipeline_

std::string l3cam_ros::RgbConfiguration::rgb_rtsp_pipeline_
private

Definition at line 731 of file rgb_configuration.cpp.

◆ rgb_saturation_

int l3cam_ros::RgbConfiguration::rgb_saturation_
private

Definition at line 722 of file rgb_configuration.cpp.

◆ rgb_sharpness_

int l3cam_ros::RgbConfiguration::rgb_sharpness_
private

Definition at line 723 of file rgb_configuration.cpp.

◆ rgb_streaming_protocol_

int l3cam_ros::RgbConfiguration::rgb_streaming_protocol_
private

Definition at line 730 of file rgb_configuration.cpp.

◆ rgb_white_balance_

int l3cam_ros::RgbConfiguration::rgb_white_balance_
private

Definition at line 727 of file rgb_configuration.cpp.

◆ server_

dynamic_reconfigure::Server<l3cam_ros::RgbConfig>* l3cam_ros::RgbConfiguration::server_
private

Definition at line 691 of file rgb_configuration.cpp.

◆ srv_brightness_

l3cam_ros::ChangeRgbCameraBrightness l3cam_ros::RgbConfiguration::srv_brightness_
private

Definition at line 694 of file rgb_configuration.cpp.

◆ srv_change_streaming_protocol_

l3cam_ros::ChangeStreamingProtocol l3cam_ros::RgbConfiguration::srv_change_streaming_protocol_
private

Definition at line 714 of file rgb_configuration.cpp.

◆ srv_contrast_

l3cam_ros::ChangeRgbCameraContrast l3cam_ros::RgbConfiguration::srv_contrast_
private

Definition at line 696 of file rgb_configuration.cpp.

◆ srv_enable_auto_exposure_time_

l3cam_ros::EnableRgbCameraAutoExposureTime l3cam_ros::RgbConfiguration::srv_enable_auto_exposure_time_
private

Definition at line 710 of file rgb_configuration.cpp.

◆ srv_enable_auto_white_balance_

l3cam_ros::EnableRgbCameraAutoWhiteBalance l3cam_ros::RgbConfiguration::srv_enable_auto_white_balance_
private

Definition at line 706 of file rgb_configuration.cpp.

◆ srv_exposure_time_

l3cam_ros::ChangeRgbCameraExposureTime l3cam_ros::RgbConfiguration::srv_exposure_time_
private

Definition at line 712 of file rgb_configuration.cpp.

◆ srv_gain_

l3cam_ros::ChangeRgbCameraGain l3cam_ros::RgbConfiguration::srv_gain_
private

Definition at line 704 of file rgb_configuration.cpp.

◆ srv_gamma_

l3cam_ros::ChangeRgbCameraGamma l3cam_ros::RgbConfiguration::srv_gamma_
private

Definition at line 702 of file rgb_configuration.cpp.

◆ srv_get_rtsp_pipeline_

l3cam_ros::GetRtspPipeline l3cam_ros::RgbConfiguration::srv_get_rtsp_pipeline_
private

Definition at line 716 of file rgb_configuration.cpp.

◆ srv_get_sensors_

l3cam_ros::GetSensorsAvailable l3cam_ros::RgbConfiguration::srv_get_sensors_

Definition at line 106 of file rgb_configuration.cpp.

◆ srv_saturation_

l3cam_ros::ChangeRgbCameraSaturation l3cam_ros::RgbConfiguration::srv_saturation_
private

Definition at line 698 of file rgb_configuration.cpp.

◆ srv_sensor_disconnected_

ros::ServiceServer l3cam_ros::RgbConfiguration::srv_sensor_disconnected_
private

Definition at line 718 of file rgb_configuration.cpp.

◆ srv_sharpness_

l3cam_ros::ChangeRgbCameraSharpness l3cam_ros::RgbConfiguration::srv_sharpness_
private

Definition at line 700 of file rgb_configuration.cpp.

◆ srv_white_balance_

l3cam_ros::ChangeRgbCameraWhiteBalance l3cam_ros::RgbConfiguration::srv_white_balance_
private

Definition at line 708 of file rgb_configuration.cpp.

◆ timeout_secs_

int l3cam_ros::RgbConfiguration::timeout_secs_

Definition at line 108 of file rgb_configuration.cpp.


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


l3cam_ros
Author(s): Beamagine
autogenerated on Wed May 28 2025 02:53:15