Public Member Functions | Public Attributes | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
l3cam_ros::L3Cam Class Reference

#include <l3cam_ros_node.hpp>

Inheritance diagram for l3cam_ros::L3Cam:
Inheritance graph
[legend]

Public Member Functions

void disconnectAll (int code)
 
int initializeDevice ()
 
 L3Cam ()
 
void spin ()
 
int startDeviceStream ()
 
- 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

l3cam m_devices [1]
 
LibL3CamStatus m_status
 

Private Member Functions

void alliedNarrowDisconnect (int code)
 
void alliedwideDisconnected (int code)
 
bool changeAlliedCameraAutoExposureTimeRange (l3cam_ros::ChangeAlliedCameraAutoExposureTimeRange::Request &req, l3cam_ros::ChangeAlliedCameraAutoExposureTimeRange::Response &res)
 
bool changeAlliedCameraAutoGainRange (l3cam_ros::ChangeAlliedCameraAutoGainRange::Request &req, l3cam_ros::ChangeAlliedCameraAutoGainRange::Response &res)
 
bool changeAlliedCameraBalanceRatio (l3cam_ros::ChangeAlliedCameraBalanceRatio::Request &req, l3cam_ros::ChangeAlliedCameraBalanceRatio::Response &res)
 
bool changeAlliedCameraBalanceRatioSelector (l3cam_ros::ChangeAlliedCameraBalanceRatioSelector::Request &req, l3cam_ros::ChangeAlliedCameraBalanceRatioSelector::Response &res)
 
bool changeAlliedCameraBalanceWhiteAutoRate (l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoRate::Request &req, l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoRate::Response &res)
 
bool changeAlliedCameraBalanceWhiteAutoTolerance (l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoTolerance::Request &req, l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoTolerance::Response &res)
 
bool changeAlliedCameraExposureTime (l3cam_ros::ChangeAlliedCameraExposureTime::Request &req, l3cam_ros::ChangeAlliedCameraExposureTime::Response &res)
 
bool changeAlliedCameraGain (l3cam_ros::ChangeAlliedCameraGain::Request &req, l3cam_ros::ChangeAlliedCameraGain::Response &res)
 
bool changeAlliedCameraGamma (l3cam_ros::ChangeAlliedCameraGamma::Request &req, l3cam_ros::ChangeAlliedCameraGamma::Response &res)
 
bool changeAlliedCameraHue (l3cam_ros::ChangeAlliedCameraHue::Request &req, l3cam_ros::ChangeAlliedCameraHue::Response &res)
 
bool changeAlliedCameraIntensityAutoPrecedence (l3cam_ros::ChangeAlliedCameraIntensityAutoPrecedence::Request &req, l3cam_ros::ChangeAlliedCameraIntensityAutoPrecedence::Response &res)
 
bool changeAlliedCameraIntensityControllerRegion (l3cam_ros::ChangeAlliedCameraIntensityControllerRegion::Request &req, l3cam_ros::ChangeAlliedCameraIntensityControllerRegion::Response &res)
 
bool changeAlliedCameraIntensityControllerTarget (l3cam_ros::ChangeAlliedCameraIntensityControllerTarget::Request &req, l3cam_ros::ChangeAlliedCameraIntensityControllerTarget::Response &res)
 
bool changeAlliedCameraSaturation (l3cam_ros::ChangeAlliedCameraSaturation::Request &req, l3cam_ros::ChangeAlliedCameraSaturation::Response &res)
 
bool changeAutobiasValue (l3cam_ros::ChangeAutobiasValue::Request &req, l3cam_ros::ChangeAutobiasValue::Response &res)
 
bool changeBiasValue (l3cam_ros::ChangeBiasValue::Request &req, l3cam_ros::ChangeBiasValue::Response &res)
 
bool changeDistanceRange (l3cam_ros::ChangeDistanceRange::Request &req, l3cam_ros::ChangeDistanceRange::Response &res)
 
bool changeNetworkConfiguration (l3cam_ros::ChangeNetworkConfiguration::Request &req, l3cam_ros::ChangeNetworkConfiguration::Response &res)
 
bool changePointcloudColor (l3cam_ros::ChangePointcloudColor::Request &req, l3cam_ros::ChangePointcloudColor::Response &res)
 
bool changePointcloudColorRange (l3cam_ros::ChangePointcloudColorRange::Request &req, l3cam_ros::ChangePointcloudColorRange::Response &res)
 
bool changePolarimetricCameraAutoExposureTimeRange (l3cam_ros::ChangePolarimetricCameraAutoExposureTimeRange::Request &req, l3cam_ros::ChangePolarimetricCameraAutoExposureTimeRange::Response &res)
 
bool changePolarimetricCameraAutoGainRange (l3cam_ros::ChangePolarimetricCameraAutoGainRange::Request &req, l3cam_ros::ChangePolarimetricCameraAutoGainRange::Response &res)
 
bool changePolarimetricCameraBlackLevel (l3cam_ros::ChangePolarimetricCameraBlackLevel::Request &req, l3cam_ros::ChangePolarimetricCameraBlackLevel::Response &res)
 
bool changePolarimetricCameraBrightness (l3cam_ros::ChangePolarimetricCameraBrightness::Request &req, l3cam_ros::ChangePolarimetricCameraBrightness::Response &res)
 
bool changePolarimetricCameraExposureTime (l3cam_ros::ChangePolarimetricCameraExposureTime::Request &req, l3cam_ros::ChangePolarimetricCameraExposureTime::Response &res)
 
bool changePolarimetricCameraGain (l3cam_ros::ChangePolarimetricCameraGain::Request &req, l3cam_ros::ChangePolarimetricCameraGain::Response &res)
 
bool changeRgbCameraBrightness (l3cam_ros::ChangeRgbCameraBrightness::Request &req, l3cam_ros::ChangeRgbCameraBrightness::Response &res)
 
bool changeRgbCameraContrast (l3cam_ros::ChangeRgbCameraContrast::Request &req, l3cam_ros::ChangeRgbCameraContrast::Response &res)
 
bool changeRgbCameraExposureTime (l3cam_ros::ChangeRgbCameraExposureTime::Request &req, l3cam_ros::ChangeRgbCameraExposureTime::Response &res)
 
bool changeRgbCameraGain (l3cam_ros::ChangeRgbCameraGain::Request &req, l3cam_ros::ChangeRgbCameraGain::Response &res)
 
bool changeRgbCameraGamma (l3cam_ros::ChangeRgbCameraGamma::Request &req, l3cam_ros::ChangeRgbCameraGamma::Response &res)
 
bool changeRgbCameraSaturation (l3cam_ros::ChangeRgbCameraSaturation::Request &req, l3cam_ros::ChangeRgbCameraSaturation::Response &res)
 
bool changeRgbCameraSharpness (l3cam_ros::ChangeRgbCameraSharpness::Request &req, l3cam_ros::ChangeRgbCameraSharpness::Response &res)
 
bool changeRgbCameraWhiteBalance (l3cam_ros::ChangeRgbCameraWhiteBalance::Request &req, l3cam_ros::ChangeRgbCameraWhiteBalance::Response &res)
 
bool changeStreamingProtocol (l3cam_ros::ChangeStreamingProtocol::Request &req, l3cam_ros::ChangeStreamingProtocol::Response &res)
 
bool changeThermalCameraColormap (l3cam_ros::ChangeThermalCameraColormap::Request &req, l3cam_ros::ChangeThermalCameraColormap::Response &res)
 
bool changeThermalCameraProcessingPipeline (l3cam_ros::ChangeThermalCameraProcessingPipeline::Request &req, l3cam_ros::ChangeThermalCameraProcessingPipeline::Response &res)
 
bool changeThermalCameraTemperatureFilter (l3cam_ros::ChangeThermalCameraTemperatureFilter::Request &req, l3cam_ros::ChangeThermalCameraTemperatureFilter::Response &res)
 
bool enableAlliedCameraAutoExposureTime (l3cam_ros::EnableAlliedCameraAutoExposureTime::Request &req, l3cam_ros::EnableAlliedCameraAutoExposureTime::Response &res)
 
bool enableAlliedCameraAutoGain (l3cam_ros::EnableAlliedCameraAutoGain::Request &req, l3cam_ros::EnableAlliedCameraAutoGain::Response &res)
 
bool enableAlliedCameraAutoWhiteBalance (l3cam_ros::EnableAlliedCameraAutoWhiteBalance::Request &req, l3cam_ros::EnableAlliedCameraAutoWhiteBalance::Response &res)
 
bool enableAutoBias (l3cam_ros::EnableAutoBias::Request &req, l3cam_ros::EnableAutoBias::Response &res)
 
bool enablePolarimetricCameraAutoExposureTime (l3cam_ros::EnablePolarimetricCameraAutoExposureTime::Request &req, l3cam_ros::EnablePolarimetricCameraAutoExposureTime::Response &res)
 
bool enablePolarimetricCameraAutoGain (l3cam_ros::EnablePolarimetricCameraAutoGain::Request &req, l3cam_ros::EnablePolarimetricCameraAutoGain::Response &res)
 
bool enableRgbCameraAutoExposureTime (l3cam_ros::EnableRgbCameraAutoExposureTime::Request &req, l3cam_ros::EnableRgbCameraAutoExposureTime::Response &res)
 
bool enableRgbCameraAutoWhiteBalance (l3cam_ros::EnableRgbCameraAutoWhiteBalance::Request &req, l3cam_ros::EnableRgbCameraAutoWhiteBalance::Response &res)
 
bool enableThermalCameraTemperatureDataUdp (l3cam_ros::EnableThermalCameraTemperatureDataUdp::Request &req, l3cam_ros::EnableThermalCameraTemperatureDataUdp::Response &res)
 
bool enableThermalCameraTemperatureFilter (l3cam_ros::EnableThermalCameraTemperatureFilter::Request &req, l3cam_ros::EnableThermalCameraTemperatureFilter::Response &res)
 
bool findDevices (l3cam_ros::FindDevices::Request &req, l3cam_ros::FindDevices::Response &res)
 
bool getAlliedCameraAutoExposureTime (l3cam_ros::GetAlliedCameraAutoExposureTime::Request &req, l3cam_ros::GetAlliedCameraAutoExposureTime::Response &res)
 
bool getAlliedCameraAutoExposureTimeRange (l3cam_ros::GetAlliedCameraAutoExposureTimeRange::Request &req, l3cam_ros::GetAlliedCameraAutoExposureTimeRange::Response &res)
 
bool getAlliedCameraAutoGain (l3cam_ros::GetAlliedCameraAutoGain::Request &req, l3cam_ros::GetAlliedCameraAutoGain::Response &res)
 
bool getAlliedCameraAutoGainRange (l3cam_ros::GetAlliedCameraAutoGainRange::Request &req, l3cam_ros::GetAlliedCameraAutoGainRange::Response &res)
 
bool getAlliedCameraAutoModeRegion (l3cam_ros::GetAlliedCameraAutoModeRegion::Request &req, l3cam_ros::GetAlliedCameraAutoModeRegion::Response &res)
 
bool getAlliedCameraAutoWhiteBalance (l3cam_ros::GetAlliedCameraAutoWhiteBalance::Request &req, l3cam_ros::GetAlliedCameraAutoWhiteBalance::Response &res)
 
bool getAlliedCameraBalanceRatio (l3cam_ros::GetAlliedCameraBalanceRatio::Request &req, l3cam_ros::GetAlliedCameraBalanceRatio::Response &res)
 
bool getAlliedCameraBalanceRatioSelector (l3cam_ros::GetAlliedCameraBalanceRatioSelector::Request &req, l3cam_ros::GetAlliedCameraBalanceRatioSelector::Response &res)
 
bool getAlliedCameraBalanceWhiteAutoRate (l3cam_ros::GetAlliedCameraBalanceWhiteAutoRate::Request &req, l3cam_ros::GetAlliedCameraBalanceWhiteAutoRate::Response &res)
 
bool getAlliedCameraBalanceWhiteAutoTolerance (l3cam_ros::GetAlliedCameraBalanceWhiteAutoTolerance::Request &req, l3cam_ros::GetAlliedCameraBalanceWhiteAutoTolerance::Response &res)
 
bool getAlliedCameraBlackLevel (l3cam_ros::GetAlliedCameraBlackLevel::Request &req, l3cam_ros::GetAlliedCameraBlackLevel::Response &res)
 
bool getAlliedCameraExposureTime (l3cam_ros::GetAlliedCameraExposureTime::Request &req, l3cam_ros::GetAlliedCameraExposureTime::Response &res)
 
bool getAlliedCameraGain (l3cam_ros::GetAlliedCameraGain::Request &req, l3cam_ros::GetAlliedCameraGain::Response &res)
 
bool getAlliedCameraGamma (l3cam_ros::GetAlliedCameraGamma::Request &req, l3cam_ros::GetAlliedCameraGamma::Response &res)
 
bool getAlliedCameraHue (l3cam_ros::GetAlliedCameraHue::Request &req, l3cam_ros::GetAlliedCameraHue::Response &res)
 
bool getAlliedCameraIntensityAutoPrecedence (l3cam_ros::GetAlliedCameraIntensityAutoPrecedence::Request &req, l3cam_ros::GetAlliedCameraIntensityAutoPrecedence::Response &res)
 
bool getAlliedCameraIntensityControllerRegion (l3cam_ros::GetAlliedCameraIntensityControllerRegion::Request &req, l3cam_ros::GetAlliedCameraIntensityControllerRegion::Response &res)
 
bool getAlliedCameraIntensityControllerTarget (l3cam_ros::GetAlliedCameraIntensityControllerTarget::Request &req, l3cam_ros::GetAlliedCameraIntensityControllerTarget::Response &res)
 
bool getAlliedCameraMaxDriverBuffersCount (l3cam_ros::GetAlliedCameraMaxDriverBuffersCount::Request &req, l3cam_ros::GetAlliedCameraMaxDriverBuffersCount::Response &res)
 
bool getAlliedCameraSaturation (l3cam_ros::GetAlliedCameraSaturation::Request &req, l3cam_ros::GetAlliedCameraSaturation::Response &res)
 
bool getAlliedCameraSharpness (l3cam_ros::GetAlliedCameraSharpness::Request &req, l3cam_ros::GetAlliedCameraSharpness::Response &res)
 
bool getAutobiasValue (l3cam_ros::GetAutobiasValue::Request &req, l3cam_ros::GetAutobiasValue::Response &res)
 
bool getDeviceInfo (l3cam_ros::GetDeviceInfo::Request &req, l3cam_ros::GetDeviceInfo::Response &res)
 
bool getDeviceStatus (l3cam_ros::GetDeviceStatus::Request &req, l3cam_ros::GetDeviceStatus::Response &res)
 
bool getDeviceTemperatures (l3cam_ros::GetDeviceTemperatures::Request &req, l3cam_ros::GetDeviceTemperatures::Response &res)
 
bool getLocalServerAddress (l3cam_ros::GetLocalServerAddress::Request &req, l3cam_ros::GetLocalServerAddress::Response &res)
 
bool getNetworkConfiguration (l3cam_ros::GetNetworkConfiguration::Request &req, l3cam_ros::GetNetworkConfiguration::Response &res)
 
bool getRtspPipeline (l3cam_ros::GetRtspPipeline::Request &req, l3cam_ros::GetRtspPipeline::Response &res)
 
bool getSensorsAvailable (l3cam_ros::GetSensorsAvailable::Request &req, l3cam_ros::GetSensorsAvailable::Response &res)
 
bool getVersion (l3cam_ros::GetVersion::Request &req, l3cam_ros::GetVersion::Response &res)
 
bool initialize (l3cam_ros::Initialize::Request &req, l3cam_ros::Initialize::Response &res)
 
void initializeAlliedNarrowServices ()
 
void initializeAlliedWideServices ()
 
void initializeLidarServices ()
 
void initializePolarimetricServices ()
 
void initializeRgbServices ()
 
void initializeServices ()
 
void initializeThermalServices ()
 
bool libL3camStatus (l3cam_ros::LibL3camStatus::Request &req, l3cam_ros::LibL3camStatus::Response &res)
 
void lidarDisconnected (int code)
 
void loadAlliedNarrowDefaultParams ()
 
void loadAlliedWideDefaultParams ()
 
void loadDefaultParams ()
 
void loadLidarDefaultParams ()
 
void loadNetworkDefaultParams ()
 
template<typename T >
void loadParam (const std::string &param_name, T &param_var, const T &default_val)
 
void loadPolarimetricDefaultParams ()
 
void loadRgbDefaultParams ()
 
void loadThermalDefaultParams ()
 
void networkDisconnected (int code)
 
void polDisconnected (int code)
 
bool powerOffDevice (l3cam_ros::PowerOffDevice::Request &req, l3cam_ros::PowerOffDevice::Response &res)
 
void printDefaultError (int error, std::string param)
 
void rgbDisconnected (int code)
 
bool setBiasShortRange (l3cam_ros::SetBiasShortRange::Request &req, l3cam_ros::SetBiasShortRange::Response &res)
 
bool setPolarimetricCameraDefaultSettings (l3cam_ros::SetPolarimetricCameraDefaultSettings::Request &req, l3cam_ros::SetPolarimetricCameraDefaultSettings::Response &res)
 
bool setRgbCameraDefaultSettings (l3cam_ros::SetRgbCameraDefaultSettings::Request &req, l3cam_ros::SetRgbCameraDefaultSettings::Response &res)
 
bool startDevice (l3cam_ros::StartDevice::Request &req, l3cam_ros::StartDevice::Response &res)
 
bool startStream (l3cam_ros::StartStream::Request &req, l3cam_ros::StartStream::Response &res)
 
bool stopDevice (l3cam_ros::StopDevice::Request &req, l3cam_ros::StopDevice::Response &res)
 
bool stopStream (l3cam_ros::StopStream::Request &req, l3cam_ros::StopStream::Response &res)
 
bool terminate (l3cam_ros::Terminate::Request &req, l3cam_ros::Terminate::Response &res)
 
void thermalDisconnected (int code)
 

Static Private Member Functions

static void errorNotification (const int32_t *error)
 

Private Attributes

ros::ServiceClient client_lidar_configuration_disconnected_
 
ros::ServiceClient client_lidar_stream_disconnected_
 
ros::ServiceClient client_narrow_configuration_disconnected_
 
ros::ServiceClient client_network_disconnected_
 
ros::ServiceClient client_pol_configuration_disconnected_
 
ros::ServiceClient client_pol_wide_stream_disconnected_
 
ros::ServiceClient client_rgb_configuration_disconnected_
 
ros::ServiceClient client_rgb_narrow_stream_disconnected_
 
ros::ServiceClient client_thermal_configuration_disconnected_
 
ros::ServiceClient client_thermal_stream_disconnected_
 
ros::ServiceClient client_wide_configuration_disconnected_
 
sensor * m_allied_narrow_sensor = NULL
 
sensor * m_allied_wide_sensor = NULL
 
sensor m_av_sensors [6]
 
sensor * m_econ_wide_sensor = NULL
 
sensor * m_lidar_sensor = NULL
 
int m_num_devices
 
sensor * m_polarimetric_sensor = NULL
 
sensor * m_rgb_sensor = NULL
 
bool m_shutdown_requested
 
sensor * m_thermal_sensor = NULL
 
ros::ServiceServer srv_change_allied_auto_exposure_time_range_
 
ros::ServiceServer srv_change_allied_auto_gain_range_
 
ros::ServiceServer srv_change_allied_balance_ratio_
 
ros::ServiceServer srv_change_allied_balance_ratio_selector_
 
ros::ServiceServer srv_change_allied_balance_white_auto_rate_
 
ros::ServiceServer srv_change_allied_balance_white_auto_tolerance_
 
ros::ServiceServer srv_change_allied_exposure_time_
 
ros::ServiceServer srv_change_allied_gain_
 
ros::ServiceServer srv_change_allied_gamma_
 
ros::ServiceServer srv_change_allied_hue_
 
ros::ServiceServer srv_change_allied_intensity_auto_precedence_
 
ros::ServiceServer srv_change_allied_intensity_controller_region_
 
ros::ServiceServer srv_change_allied_intensity_controller_target_
 
ros::ServiceServer srv_change_allied_saturation_
 
ros::ServiceServer srv_change_autobias_value_
 
ros::ServiceServer srv_change_bias_value_
 
ros::ServiceServer srv_change_distance_range_
 
ros::ServiceServer srv_change_network_configuration_
 
ros::ServiceServer srv_change_pointcloud_color_
 
ros::ServiceServer srv_change_pointcloud_color_range_
 
ros::ServiceServer srv_change_polarimetric_auto_exposure_time_range_
 
ros::ServiceServer srv_change_polarimetric_auto_gain_range_
 
ros::ServiceServer srv_change_polarimetric_black_level_
 
ros::ServiceServer srv_change_polarimetric_brightness_
 
ros::ServiceServer srv_change_polarimetric_exposure_time_
 
ros::ServiceServer srv_change_polarimetric_gain_
 
ros::ServiceServer srv_change_rgb_brightness_
 
ros::ServiceServer srv_change_rgb_contrast_
 
ros::ServiceServer srv_change_rgb_exposure_time_
 
ros::ServiceServer srv_change_rgb_gain_
 
ros::ServiceServer srv_change_rgb_gamma_
 
ros::ServiceServer srv_change_rgb_saturation_
 
ros::ServiceServer srv_change_rgb_sharpness_
 
ros::ServiceServer srv_change_rgb_white_balance_
 
ros::ServiceServer srv_change_streaming_protocol_
 
ros::ServiceServer srv_change_thermal_colormap_
 
ros::ServiceServer srv_change_thermal_processing_pipeline_
 
ros::ServiceServer srv_change_thermal_temperature_filter_
 
ros::ServiceServer srv_enable_allied_auto_exposure_time_
 
ros::ServiceServer srv_enable_allied_auto_gain_
 
ros::ServiceServer srv_enable_allied_auto_white_balance_
 
ros::ServiceServer srv_enable_auto_bias_
 
ros::ServiceServer srv_enable_polarimetric_auto_exposure_time_
 
ros::ServiceServer srv_enable_polarimetric_auto_gain_
 
ros::ServiceServer srv_enable_rgb_auto_exposure_time_
 
ros::ServiceServer srv_enable_rgb_auto_white_balance_
 
ros::ServiceServer srv_enable_thermal_temperature_data_udp_
 
ros::ServiceServer srv_enable_thermal_temperature_filter_
 
ros::ServiceServer srv_find_devices_
 
ros::ServiceServer srv_get_allied_auto_exposure_time_
 
ros::ServiceServer srv_get_allied_auto_exposure_time_range_
 
ros::ServiceServer srv_get_allied_auto_gain_
 
ros::ServiceServer srv_get_allied_auto_gain_range_
 
ros::ServiceServer srv_get_allied_auto_mode_region_
 
ros::ServiceServer srv_get_allied_auto_white_balance_
 
ros::ServiceServer srv_get_allied_balance_ratio_
 
ros::ServiceServer srv_get_allied_balance_ratio_selector_
 
ros::ServiceServer srv_get_allied_balance_white_auto_rate_
 
ros::ServiceServer srv_get_allied_balance_white_auto_tolerance_
 
ros::ServiceServer srv_get_allied_black_level_
 
ros::ServiceServer srv_get_allied_exposure_time_
 
ros::ServiceServer srv_get_allied_gain_
 
ros::ServiceServer srv_get_allied_gamma_
 
ros::ServiceServer srv_get_allied_hue_
 
ros::ServiceServer srv_get_allied_intensity_auto_precedence_
 
ros::ServiceServer srv_get_allied_intensity_controller_region_
 
ros::ServiceServer srv_get_allied_intensity_controller_target_
 
ros::ServiceServer srv_get_allied_max_driver_buffers_count_
 
ros::ServiceServer srv_get_allied_saturation_
 
ros::ServiceServer srv_get_allied_sharpness_
 
ros::ServiceServer srv_get_autobias_value_
 
ros::ServiceServer srv_get_device_info_
 
ros::ServiceServer srv_get_device_status_
 
ros::ServiceServer srv_get_device_temperatures_
 
ros::ServiceServer srv_get_local_server_address_
 
ros::ServiceServer srv_get_network_configuration_
 
ros::ServiceServer srv_get_rtsp_pipeline_
 
ros::ServiceServer srv_get_sensors_available_
 
ros::ServiceServer srv_get_version_
 
ros::ServiceServer srv_initialize_
 
ros::ServiceServer srv_libl3cam_status_
 
l3cam_ros::SensorDisconnected srv_narrow_configuration_disconnected_
 
l3cam_ros::SensorDisconnected srv_network_disconnected_
 
l3cam_ros::SensorDisconnected srv_pointcloud_configuration_disconnected_
 
l3cam_ros::SensorDisconnected srv_pointcloud_stream_disconnected_
 
l3cam_ros::SensorDisconnected srv_pol_configuration_disconnected_
 
l3cam_ros::SensorDisconnected srv_pol_wide_stream_disconnected_
 
ros::ServiceServer srv_power_off_device_
 
l3cam_ros::SensorDisconnected srv_rgb_configuration_disconnected_
 
l3cam_ros::SensorDisconnected srv_rgb_narrow_stream_disconnected_
 
ros::ServiceServer srv_set_bias_short_range_
 
ros::ServiceServer srv_set_polarimetric_default_settings_
 
ros::ServiceServer srv_set_rgb_default_settings_
 
ros::ServiceServer srv_start_device_
 
ros::ServiceServer srv_start_stream_
 
ros::ServiceServer srv_stop_device_
 
ros::ServiceServer srv_stop_stream_
 
ros::ServiceServer srv_terminate_
 
l3cam_ros::SensorDisconnected srv_thermal_configuration_disconnected_
 
l3cam_ros::SensorDisconnected srv_thermal_stream_disconnected_
 
l3cam_ros::SensorDisconnected srv_wide_configuration_disconnected_
 
int timeout_secs_
 

Detailed Description

Definition at line 135 of file l3cam_ros_node.hpp.

Constructor & Destructor Documentation

◆ L3Cam()

l3cam_ros::L3Cam::L3Cam ( )
explicit

Definition at line 45 of file l3cam_ros_node.cpp.

Member Function Documentation

◆ alliedNarrowDisconnect()

void l3cam_ros::L3Cam::alliedNarrowDisconnect ( int  code)
private

Definition at line 2190 of file l3cam_ros_node.cpp.

◆ alliedwideDisconnected()

void l3cam_ros::L3Cam::alliedwideDisconnected ( int  code)
private

Definition at line 2173 of file l3cam_ros_node.cpp.

◆ changeAlliedCameraAutoExposureTimeRange()

bool l3cam_ros::L3Cam::changeAlliedCameraAutoExposureTimeRange ( l3cam_ros::ChangeAlliedCameraAutoExposureTimeRange::Request &  req,
l3cam_ros::ChangeAlliedCameraAutoExposureTimeRange::Response &  res 
)
private

Definition at line 1510 of file l3cam_ros_node.cpp.

◆ changeAlliedCameraAutoGainRange()

bool l3cam_ros::L3Cam::changeAlliedCameraAutoGainRange ( l3cam_ros::ChangeAlliedCameraAutoGainRange::Request &  req,
l3cam_ros::ChangeAlliedCameraAutoGainRange::Response &  res 
)
private

Definition at line 1558 of file l3cam_ros_node.cpp.

◆ changeAlliedCameraBalanceRatio()

bool l3cam_ros::L3Cam::changeAlliedCameraBalanceRatio ( l3cam_ros::ChangeAlliedCameraBalanceRatio::Request &  req,
l3cam_ros::ChangeAlliedCameraBalanceRatio::Response &  res 
)
private

Definition at line 1670 of file l3cam_ros_node.cpp.

◆ changeAlliedCameraBalanceRatioSelector()

bool l3cam_ros::L3Cam::changeAlliedCameraBalanceRatioSelector ( l3cam_ros::ChangeAlliedCameraBalanceRatioSelector::Request &  req,
l3cam_ros::ChangeAlliedCameraBalanceRatioSelector::Response &  res 
)
private

Definition at line 1654 of file l3cam_ros_node.cpp.

◆ changeAlliedCameraBalanceWhiteAutoRate()

bool l3cam_ros::L3Cam::changeAlliedCameraBalanceWhiteAutoRate ( l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoRate::Request &  req,
l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoRate::Response &  res 
)
private

Definition at line 1686 of file l3cam_ros_node.cpp.

◆ changeAlliedCameraBalanceWhiteAutoTolerance()

bool l3cam_ros::L3Cam::changeAlliedCameraBalanceWhiteAutoTolerance ( l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoTolerance::Request &  req,
l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoTolerance::Response &  res 
)
private

Definition at line 1702 of file l3cam_ros_node.cpp.

◆ changeAlliedCameraExposureTime()

bool l3cam_ros::L3Cam::changeAlliedCameraExposureTime ( l3cam_ros::ChangeAlliedCameraExposureTime::Request &  req,
l3cam_ros::ChangeAlliedCameraExposureTime::Response &  res 
)
private

Definition at line 1478 of file l3cam_ros_node.cpp.

◆ changeAlliedCameraGain()

bool l3cam_ros::L3Cam::changeAlliedCameraGain ( l3cam_ros::ChangeAlliedCameraGain::Request &  req,
l3cam_ros::ChangeAlliedCameraGain::Response &  res 
)
private

Definition at line 1526 of file l3cam_ros_node.cpp.

◆ changeAlliedCameraGamma()

bool l3cam_ros::L3Cam::changeAlliedCameraGamma ( l3cam_ros::ChangeAlliedCameraGamma::Request &  req,
l3cam_ros::ChangeAlliedCameraGamma::Response &  res 
)
private

Definition at line 1574 of file l3cam_ros_node.cpp.

◆ changeAlliedCameraHue()

bool l3cam_ros::L3Cam::changeAlliedCameraHue ( l3cam_ros::ChangeAlliedCameraHue::Request &  req,
l3cam_ros::ChangeAlliedCameraHue::Response &  res 
)
private

Definition at line 1606 of file l3cam_ros_node.cpp.

◆ changeAlliedCameraIntensityAutoPrecedence()

bool l3cam_ros::L3Cam::changeAlliedCameraIntensityAutoPrecedence ( l3cam_ros::ChangeAlliedCameraIntensityAutoPrecedence::Request &  req,
l3cam_ros::ChangeAlliedCameraIntensityAutoPrecedence::Response &  res 
)
private

Definition at line 1622 of file l3cam_ros_node.cpp.

◆ changeAlliedCameraIntensityControllerRegion()

bool l3cam_ros::L3Cam::changeAlliedCameraIntensityControllerRegion ( l3cam_ros::ChangeAlliedCameraIntensityControllerRegion::Request &  req,
l3cam_ros::ChangeAlliedCameraIntensityControllerRegion::Response &  res 
)
private

Definition at line 1718 of file l3cam_ros_node.cpp.

◆ changeAlliedCameraIntensityControllerTarget()

bool l3cam_ros::L3Cam::changeAlliedCameraIntensityControllerTarget ( l3cam_ros::ChangeAlliedCameraIntensityControllerTarget::Request &  req,
l3cam_ros::ChangeAlliedCameraIntensityControllerTarget::Response &  res 
)
private

Definition at line 1734 of file l3cam_ros_node.cpp.

◆ changeAlliedCameraSaturation()

bool l3cam_ros::L3Cam::changeAlliedCameraSaturation ( l3cam_ros::ChangeAlliedCameraSaturation::Request &  req,
l3cam_ros::ChangeAlliedCameraSaturation::Response &  res 
)
private

Definition at line 1590 of file l3cam_ros_node.cpp.

◆ changeAutobiasValue()

bool l3cam_ros::L3Cam::changeAutobiasValue ( l3cam_ros::ChangeAutobiasValue::Request &  req,
l3cam_ros::ChangeAutobiasValue::Response &  res 
)
private

Definition at line 1308 of file l3cam_ros_node.cpp.

◆ changeBiasValue()

bool l3cam_ros::L3Cam::changeBiasValue ( l3cam_ros::ChangeBiasValue::Request &  req,
l3cam_ros::ChangeBiasValue::Response &  res 
)
private

Definition at line 1302 of file l3cam_ros_node.cpp.

◆ changeDistanceRange()

bool l3cam_ros::L3Cam::changeDistanceRange ( l3cam_ros::ChangeDistanceRange::Request &  req,
l3cam_ros::ChangeDistanceRange::Response &  res 
)
private

Definition at line 1284 of file l3cam_ros_node.cpp.

◆ changeNetworkConfiguration()

bool l3cam_ros::L3Cam::changeNetworkConfiguration ( l3cam_ros::ChangeNetworkConfiguration::Request &  req,
l3cam_ros::ChangeNetworkConfiguration::Response &  res 
)
private

Definition at line 1159 of file l3cam_ros_node.cpp.

◆ changePointcloudColor()

bool l3cam_ros::L3Cam::changePointcloudColor ( l3cam_ros::ChangePointcloudColor::Request &  req,
l3cam_ros::ChangePointcloudColor::Response &  res 
)
private

Definition at line 1272 of file l3cam_ros_node.cpp.

◆ changePointcloudColorRange()

bool l3cam_ros::L3Cam::changePointcloudColorRange ( l3cam_ros::ChangePointcloudColorRange::Request &  req,
l3cam_ros::ChangePointcloudColorRange::Response &  res 
)
private

Definition at line 1278 of file l3cam_ros_node.cpp.

◆ changePolarimetricCameraAutoExposureTimeRange()

bool l3cam_ros::L3Cam::changePolarimetricCameraAutoExposureTimeRange ( l3cam_ros::ChangePolarimetricCameraAutoExposureTimeRange::Request &  req,
l3cam_ros::ChangePolarimetricCameraAutoExposureTimeRange::Response &  res 
)
private

Definition at line 1366 of file l3cam_ros_node.cpp.

◆ changePolarimetricCameraAutoGainRange()

bool l3cam_ros::L3Cam::changePolarimetricCameraAutoGainRange ( l3cam_ros::ChangePolarimetricCameraAutoGainRange::Request &  req,
l3cam_ros::ChangePolarimetricCameraAutoGainRange::Response &  res 
)
private

Definition at line 1348 of file l3cam_ros_node.cpp.

◆ changePolarimetricCameraBlackLevel()

bool l3cam_ros::L3Cam::changePolarimetricCameraBlackLevel ( l3cam_ros::ChangePolarimetricCameraBlackLevel::Request &  req,
l3cam_ros::ChangePolarimetricCameraBlackLevel::Response &  res 
)
private

Definition at line 1336 of file l3cam_ros_node.cpp.

◆ changePolarimetricCameraBrightness()

bool l3cam_ros::L3Cam::changePolarimetricCameraBrightness ( l3cam_ros::ChangePolarimetricCameraBrightness::Request &  req,
l3cam_ros::ChangePolarimetricCameraBrightness::Response &  res 
)
private

Definition at line 1330 of file l3cam_ros_node.cpp.

◆ changePolarimetricCameraExposureTime()

bool l3cam_ros::L3Cam::changePolarimetricCameraExposureTime ( l3cam_ros::ChangePolarimetricCameraExposureTime::Request &  req,
l3cam_ros::ChangePolarimetricCameraExposureTime::Response &  res 
)
private

Definition at line 1372 of file l3cam_ros_node.cpp.

◆ changePolarimetricCameraGain()

bool l3cam_ros::L3Cam::changePolarimetricCameraGain ( l3cam_ros::ChangePolarimetricCameraGain::Request &  req,
l3cam_ros::ChangePolarimetricCameraGain::Response &  res 
)
private

Definition at line 1354 of file l3cam_ros_node.cpp.

◆ changeRgbCameraBrightness()

bool l3cam_ros::L3Cam::changeRgbCameraBrightness ( l3cam_ros::ChangeRgbCameraBrightness::Request &  req,
l3cam_ros::ChangeRgbCameraBrightness::Response &  res 
)
private

Definition at line 1386 of file l3cam_ros_node.cpp.

◆ changeRgbCameraContrast()

bool l3cam_ros::L3Cam::changeRgbCameraContrast ( l3cam_ros::ChangeRgbCameraContrast::Request &  req,
l3cam_ros::ChangeRgbCameraContrast::Response &  res 
)
private

Definition at line 1392 of file l3cam_ros_node.cpp.

◆ changeRgbCameraExposureTime()

bool l3cam_ros::L3Cam::changeRgbCameraExposureTime ( l3cam_ros::ChangeRgbCameraExposureTime::Request &  req,
l3cam_ros::ChangeRgbCameraExposureTime::Response &  res 
)
private

Definition at line 1440 of file l3cam_ros_node.cpp.

◆ changeRgbCameraGain()

bool l3cam_ros::L3Cam::changeRgbCameraGain ( l3cam_ros::ChangeRgbCameraGain::Request &  req,
l3cam_ros::ChangeRgbCameraGain::Response &  res 
)
private

Definition at line 1416 of file l3cam_ros_node.cpp.

◆ changeRgbCameraGamma()

bool l3cam_ros::L3Cam::changeRgbCameraGamma ( l3cam_ros::ChangeRgbCameraGamma::Request &  req,
l3cam_ros::ChangeRgbCameraGamma::Response &  res 
)
private

Definition at line 1410 of file l3cam_ros_node.cpp.

◆ changeRgbCameraSaturation()

bool l3cam_ros::L3Cam::changeRgbCameraSaturation ( l3cam_ros::ChangeRgbCameraSaturation::Request &  req,
l3cam_ros::ChangeRgbCameraSaturation::Response &  res 
)
private

Definition at line 1398 of file l3cam_ros_node.cpp.

◆ changeRgbCameraSharpness()

bool l3cam_ros::L3Cam::changeRgbCameraSharpness ( l3cam_ros::ChangeRgbCameraSharpness::Request &  req,
l3cam_ros::ChangeRgbCameraSharpness::Response &  res 
)
private

Definition at line 1404 of file l3cam_ros_node.cpp.

◆ changeRgbCameraWhiteBalance()

bool l3cam_ros::L3Cam::changeRgbCameraWhiteBalance ( l3cam_ros::ChangeRgbCameraWhiteBalance::Request &  req,
l3cam_ros::ChangeRgbCameraWhiteBalance::Response &  res 
)
private

Definition at line 1428 of file l3cam_ros_node.cpp.

◆ changeStreamingProtocol()

bool l3cam_ros::L3Cam::changeStreamingProtocol ( l3cam_ros::ChangeStreamingProtocol::Request &  req,
l3cam_ros::ChangeStreamingProtocol::Response &  res 
)
private

Definition at line 1051 of file l3cam_ros_node.cpp.

◆ changeThermalCameraColormap()

bool l3cam_ros::L3Cam::changeThermalCameraColormap ( l3cam_ros::ChangeThermalCameraColormap::Request &  req,
l3cam_ros::ChangeThermalCameraColormap::Response &  res 
)
private

Definition at line 1447 of file l3cam_ros_node.cpp.

◆ changeThermalCameraProcessingPipeline()

bool l3cam_ros::L3Cam::changeThermalCameraProcessingPipeline ( l3cam_ros::ChangeThermalCameraProcessingPipeline::Request &  req,
l3cam_ros::ChangeThermalCameraProcessingPipeline::Response &  res 
)
private

Definition at line 1465 of file l3cam_ros_node.cpp.

◆ changeThermalCameraTemperatureFilter()

bool l3cam_ros::L3Cam::changeThermalCameraTemperatureFilter ( l3cam_ros::ChangeThermalCameraTemperatureFilter::Request &  req,
l3cam_ros::ChangeThermalCameraTemperatureFilter::Response &  res 
)
private

Definition at line 1459 of file l3cam_ros_node.cpp.

◆ disconnectAll()

void l3cam_ros::L3Cam::disconnectAll ( int  code)

Definition at line 198 of file l3cam_ros_node.cpp.

◆ enableAlliedCameraAutoExposureTime()

bool l3cam_ros::L3Cam::enableAlliedCameraAutoExposureTime ( l3cam_ros::EnableAlliedCameraAutoExposureTime::Request &  req,
l3cam_ros::EnableAlliedCameraAutoExposureTime::Response &  res 
)
private

Definition at line 1494 of file l3cam_ros_node.cpp.

◆ enableAlliedCameraAutoGain()

bool l3cam_ros::L3Cam::enableAlliedCameraAutoGain ( l3cam_ros::EnableAlliedCameraAutoGain::Request &  req,
l3cam_ros::EnableAlliedCameraAutoGain::Response &  res 
)
private

Definition at line 1542 of file l3cam_ros_node.cpp.

◆ enableAlliedCameraAutoWhiteBalance()

bool l3cam_ros::L3Cam::enableAlliedCameraAutoWhiteBalance ( l3cam_ros::EnableAlliedCameraAutoWhiteBalance::Request &  req,
l3cam_ros::EnableAlliedCameraAutoWhiteBalance::Response &  res 
)
private

Definition at line 1638 of file l3cam_ros_node.cpp.

◆ enableAutoBias()

bool l3cam_ros::L3Cam::enableAutoBias ( l3cam_ros::EnableAutoBias::Request &  req,
l3cam_ros::EnableAutoBias::Response &  res 
)
private

Definition at line 1296 of file l3cam_ros_node.cpp.

◆ enablePolarimetricCameraAutoExposureTime()

bool l3cam_ros::L3Cam::enablePolarimetricCameraAutoExposureTime ( l3cam_ros::EnablePolarimetricCameraAutoExposureTime::Request &  req,
l3cam_ros::EnablePolarimetricCameraAutoExposureTime::Response &  res 
)
private

Definition at line 1360 of file l3cam_ros_node.cpp.

◆ enablePolarimetricCameraAutoGain()

bool l3cam_ros::L3Cam::enablePolarimetricCameraAutoGain ( l3cam_ros::EnablePolarimetricCameraAutoGain::Request &  req,
l3cam_ros::EnablePolarimetricCameraAutoGain::Response &  res 
)
private

Definition at line 1342 of file l3cam_ros_node.cpp.

◆ enableRgbCameraAutoExposureTime()

bool l3cam_ros::L3Cam::enableRgbCameraAutoExposureTime ( l3cam_ros::EnableRgbCameraAutoExposureTime::Request &  req,
l3cam_ros::EnableRgbCameraAutoExposureTime::Response &  res 
)
private

Definition at line 1434 of file l3cam_ros_node.cpp.

◆ enableRgbCameraAutoWhiteBalance()

bool l3cam_ros::L3Cam::enableRgbCameraAutoWhiteBalance ( l3cam_ros::EnableRgbCameraAutoWhiteBalance::Request &  req,
l3cam_ros::EnableRgbCameraAutoWhiteBalance::Response &  res 
)
private

Definition at line 1422 of file l3cam_ros_node.cpp.

◆ enableThermalCameraTemperatureDataUdp()

bool l3cam_ros::L3Cam::enableThermalCameraTemperatureDataUdp ( l3cam_ros::EnableThermalCameraTemperatureDataUdp::Request &  req,
l3cam_ros::EnableThermalCameraTemperatureDataUdp::Response &  res 
)
private

Definition at line 1471 of file l3cam_ros_node.cpp.

◆ enableThermalCameraTemperatureFilter()

bool l3cam_ros::L3Cam::enableThermalCameraTemperatureFilter ( l3cam_ros::EnableThermalCameraTemperatureFilter::Request &  req,
l3cam_ros::EnableThermalCameraTemperatureFilter::Response &  res 
)
private

Definition at line 1453 of file l3cam_ros_node.cpp.

◆ errorNotification()

void l3cam_ros::L3Cam::errorNotification ( const int32_t *  error)
staticprivate

Definition at line 2207 of file l3cam_ros_node.cpp.

◆ findDevices()

bool l3cam_ros::L3Cam::findDevices ( l3cam_ros::FindDevices::Request &  req,
l3cam_ros::FindDevices::Response &  res 
)
private

Definition at line 1003 of file l3cam_ros_node.cpp.

◆ getAlliedCameraAutoExposureTime()

bool l3cam_ros::L3Cam::getAlliedCameraAutoExposureTime ( l3cam_ros::GetAlliedCameraAutoExposureTime::Request &  req,
l3cam_ros::GetAlliedCameraAutoExposureTime::Response &  res 
)
private

Definition at line 1782 of file l3cam_ros_node.cpp.

◆ getAlliedCameraAutoExposureTimeRange()

bool l3cam_ros::L3Cam::getAlliedCameraAutoExposureTimeRange ( l3cam_ros::GetAlliedCameraAutoExposureTimeRange::Request &  req,
l3cam_ros::GetAlliedCameraAutoExposureTimeRange::Response &  res 
)
private

Definition at line 1801 of file l3cam_ros_node.cpp.

◆ getAlliedCameraAutoGain()

bool l3cam_ros::L3Cam::getAlliedCameraAutoGain ( l3cam_ros::GetAlliedCameraAutoGain::Request &  req,
l3cam_ros::GetAlliedCameraAutoGain::Response &  res 
)
private

Definition at line 1833 of file l3cam_ros_node.cpp.

◆ getAlliedCameraAutoGainRange()

bool l3cam_ros::L3Cam::getAlliedCameraAutoGainRange ( l3cam_ros::GetAlliedCameraAutoGainRange::Request &  req,
l3cam_ros::GetAlliedCameraAutoGainRange::Response &  res 
)
private

Definition at line 1852 of file l3cam_ros_node.cpp.

◆ getAlliedCameraAutoModeRegion()

bool l3cam_ros::L3Cam::getAlliedCameraAutoModeRegion ( l3cam_ros::GetAlliedCameraAutoModeRegion::Request &  req,
l3cam_ros::GetAlliedCameraAutoModeRegion::Response &  res 
)
private

Definition at line 2031 of file l3cam_ros_node.cpp.

◆ getAlliedCameraAutoWhiteBalance()

bool l3cam_ros::L3Cam::getAlliedCameraAutoWhiteBalance ( l3cam_ros::GetAlliedCameraAutoWhiteBalance::Request &  req,
l3cam_ros::GetAlliedCameraAutoWhiteBalance::Response &  res 
)
private

Definition at line 1948 of file l3cam_ros_node.cpp.

◆ getAlliedCameraBalanceRatio()

bool l3cam_ros::L3Cam::getAlliedCameraBalanceRatio ( l3cam_ros::GetAlliedCameraBalanceRatio::Request &  req,
l3cam_ros::GetAlliedCameraBalanceRatio::Response &  res 
)
private

Definition at line 1983 of file l3cam_ros_node.cpp.

◆ getAlliedCameraBalanceRatioSelector()

bool l3cam_ros::L3Cam::getAlliedCameraBalanceRatioSelector ( l3cam_ros::GetAlliedCameraBalanceRatioSelector::Request &  req,
l3cam_ros::GetAlliedCameraBalanceRatioSelector::Response &  res 
)
private

Definition at line 1967 of file l3cam_ros_node.cpp.

◆ getAlliedCameraBalanceWhiteAutoRate()

bool l3cam_ros::L3Cam::getAlliedCameraBalanceWhiteAutoRate ( l3cam_ros::GetAlliedCameraBalanceWhiteAutoRate::Request &  req,
l3cam_ros::GetAlliedCameraBalanceWhiteAutoRate::Response &  res 
)
private

Definition at line 1999 of file l3cam_ros_node.cpp.

◆ getAlliedCameraBalanceWhiteAutoTolerance()

bool l3cam_ros::L3Cam::getAlliedCameraBalanceWhiteAutoTolerance ( l3cam_ros::GetAlliedCameraBalanceWhiteAutoTolerance::Request &  req,
l3cam_ros::GetAlliedCameraBalanceWhiteAutoTolerance::Response &  res 
)
private

Definition at line 2015 of file l3cam_ros_node.cpp.

◆ getAlliedCameraBlackLevel()

bool l3cam_ros::L3Cam::getAlliedCameraBlackLevel ( l3cam_ros::GetAlliedCameraBlackLevel::Request &  req,
l3cam_ros::GetAlliedCameraBlackLevel::Response &  res 
)
private

Definition at line 1750 of file l3cam_ros_node.cpp.

◆ getAlliedCameraExposureTime()

bool l3cam_ros::L3Cam::getAlliedCameraExposureTime ( l3cam_ros::GetAlliedCameraExposureTime::Request &  req,
l3cam_ros::GetAlliedCameraExposureTime::Response &  res 
)
private

Definition at line 1766 of file l3cam_ros_node.cpp.

◆ getAlliedCameraGain()

bool l3cam_ros::L3Cam::getAlliedCameraGain ( l3cam_ros::GetAlliedCameraGain::Request &  req,
l3cam_ros::GetAlliedCameraGain::Response &  res 
)
private

Definition at line 1817 of file l3cam_ros_node.cpp.

◆ getAlliedCameraGamma()

bool l3cam_ros::L3Cam::getAlliedCameraGamma ( l3cam_ros::GetAlliedCameraGamma::Request &  req,
l3cam_ros::GetAlliedCameraGamma::Response &  res 
)
private

Definition at line 1868 of file l3cam_ros_node.cpp.

◆ getAlliedCameraHue()

bool l3cam_ros::L3Cam::getAlliedCameraHue ( l3cam_ros::GetAlliedCameraHue::Request &  req,
l3cam_ros::GetAlliedCameraHue::Response &  res 
)
private

Definition at line 1916 of file l3cam_ros_node.cpp.

◆ getAlliedCameraIntensityAutoPrecedence()

bool l3cam_ros::L3Cam::getAlliedCameraIntensityAutoPrecedence ( l3cam_ros::GetAlliedCameraIntensityAutoPrecedence::Request &  req,
l3cam_ros::GetAlliedCameraIntensityAutoPrecedence::Response &  res 
)
private

Definition at line 1932 of file l3cam_ros_node.cpp.

◆ getAlliedCameraIntensityControllerRegion()

bool l3cam_ros::L3Cam::getAlliedCameraIntensityControllerRegion ( l3cam_ros::GetAlliedCameraIntensityControllerRegion::Request &  req,
l3cam_ros::GetAlliedCameraIntensityControllerRegion::Response &  res 
)
private

Definition at line 2047 of file l3cam_ros_node.cpp.

◆ getAlliedCameraIntensityControllerTarget()

bool l3cam_ros::L3Cam::getAlliedCameraIntensityControllerTarget ( l3cam_ros::GetAlliedCameraIntensityControllerTarget::Request &  req,
l3cam_ros::GetAlliedCameraIntensityControllerTarget::Response &  res 
)
private

Definition at line 2063 of file l3cam_ros_node.cpp.

◆ getAlliedCameraMaxDriverBuffersCount()

bool l3cam_ros::L3Cam::getAlliedCameraMaxDriverBuffersCount ( l3cam_ros::GetAlliedCameraMaxDriverBuffersCount::Request &  req,
l3cam_ros::GetAlliedCameraMaxDriverBuffersCount::Response &  res 
)
private

Definition at line 2079 of file l3cam_ros_node.cpp.

◆ getAlliedCameraSaturation()

bool l3cam_ros::L3Cam::getAlliedCameraSaturation ( l3cam_ros::GetAlliedCameraSaturation::Request &  req,
l3cam_ros::GetAlliedCameraSaturation::Response &  res 
)
private

Definition at line 1884 of file l3cam_ros_node.cpp.

◆ getAlliedCameraSharpness()

bool l3cam_ros::L3Cam::getAlliedCameraSharpness ( l3cam_ros::GetAlliedCameraSharpness::Request &  req,
l3cam_ros::GetAlliedCameraSharpness::Response &  res 
)
private

Definition at line 1900 of file l3cam_ros_node.cpp.

◆ getAutobiasValue()

bool l3cam_ros::L3Cam::getAutobiasValue ( l3cam_ros::GetAutobiasValue::Request &  req,
l3cam_ros::GetAutobiasValue::Response &  res 
)
private

Definition at line 1314 of file l3cam_ros_node.cpp.

◆ getDeviceInfo()

bool l3cam_ros::L3Cam::getDeviceInfo ( l3cam_ros::GetDeviceInfo::Request &  req,
l3cam_ros::GetDeviceInfo::Response &  res 
)
private

Definition at line 1017 of file l3cam_ros_node.cpp.

◆ getDeviceStatus()

bool l3cam_ros::L3Cam::getDeviceStatus ( l3cam_ros::GetDeviceStatus::Request &  req,
l3cam_ros::GetDeviceStatus::Response &  res 
)
private

Definition at line 1027 of file l3cam_ros_node.cpp.

◆ getDeviceTemperatures()

bool l3cam_ros::L3Cam::getDeviceTemperatures ( l3cam_ros::GetDeviceTemperatures::Request &  req,
l3cam_ros::GetDeviceTemperatures::Response &  res 
)
private

Definition at line 1231 of file l3cam_ros_node.cpp.

◆ getLocalServerAddress()

bool l3cam_ros::L3Cam::getLocalServerAddress ( l3cam_ros::GetLocalServerAddress::Request &  req,
l3cam_ros::GetLocalServerAddress::Response &  res 
)
private

Definition at line 1010 of file l3cam_ros_node.cpp.

◆ getNetworkConfiguration()

bool l3cam_ros::L3Cam::getNetworkConfiguration ( l3cam_ros::GetNetworkConfiguration::Request &  req,
l3cam_ros::GetNetworkConfiguration::Response &  res 
)
private

Definition at line 1146 of file l3cam_ros_node.cpp.

◆ getRtspPipeline()

bool l3cam_ros::L3Cam::getRtspPipeline ( l3cam_ros::GetRtspPipeline::Request &  req,
l3cam_ros::GetRtspPipeline::Response &  res 
)
private

Definition at line 1108 of file l3cam_ros_node.cpp.

◆ getSensorsAvailable()

bool l3cam_ros::L3Cam::getSensorsAvailable ( l3cam_ros::GetSensorsAvailable::Request &  req,
l3cam_ros::GetSensorsAvailable::Response &  res 
)
private

Definition at line 1034 of file l3cam_ros_node.cpp.

◆ getVersion()

bool l3cam_ros::L3Cam::getVersion ( l3cam_ros::GetVersion::Request &  req,
l3cam_ros::GetVersion::Response &  res 
)
private

Definition at line 966 of file l3cam_ros_node.cpp.

◆ initialize()

bool l3cam_ros::L3Cam::initialize ( l3cam_ros::Initialize::Request &  req,
l3cam_ros::Initialize::Response &  res 
)
private

Definition at line 973 of file l3cam_ros_node.cpp.

◆ initializeAlliedNarrowServices()

void l3cam_ros::L3Cam::initializeAlliedNarrowServices ( )
private

Definition at line 390 of file l3cam_ros_node.cpp.

◆ initializeAlliedWideServices()

void l3cam_ros::L3Cam::initializeAlliedWideServices ( )
private

Definition at line 344 of file l3cam_ros_node.cpp.

◆ initializeDevice()

int l3cam_ros::L3Cam::initializeDevice ( )

Definition at line 82 of file l3cam_ros_node.cpp.

◆ initializeLidarServices()

void l3cam_ros::L3Cam::initializeLidarServices ( )
private

Definition at line 283 of file l3cam_ros_node.cpp.

◆ initializePolarimetricServices()

void l3cam_ros::L3Cam::initializePolarimetricServices ( )
private

Definition at line 298 of file l3cam_ros_node.cpp.

◆ initializeRgbServices()

void l3cam_ros::L3Cam::initializeRgbServices ( )
private

Definition at line 314 of file l3cam_ros_node.cpp.

◆ initializeServices()

void l3cam_ros::L3Cam::initializeServices ( )
private

Definition at line 228 of file l3cam_ros_node.cpp.

◆ initializeThermalServices()

void l3cam_ros::L3Cam::initializeThermalServices ( )
private

Definition at line 332 of file l3cam_ros_node.cpp.

◆ libL3camStatus()

bool l3cam_ros::L3Cam::libL3camStatus ( l3cam_ros::LibL3camStatus::Request &  req,
l3cam_ros::LibL3camStatus::Response &  res 
)
private

Definition at line 959 of file l3cam_ros_node.cpp.

◆ lidarDisconnected()

void l3cam_ros::L3Cam::lidarDisconnected ( int  code)
private

Definition at line 2105 of file l3cam_ros_node.cpp.

◆ loadAlliedNarrowDefaultParams()

void l3cam_ros::L3Cam::loadAlliedNarrowDefaultParams ( )
private

Definition at line 859 of file l3cam_ros_node.cpp.

◆ loadAlliedWideDefaultParams()

void l3cam_ros::L3Cam::loadAlliedWideDefaultParams ( )
private

Definition at line 760 of file l3cam_ros_node.cpp.

◆ loadDefaultParams()

void l3cam_ros::L3Cam::loadDefaultParams ( )
private

Definition at line 465 of file l3cam_ros_node.cpp.

◆ loadLidarDefaultParams()

void l3cam_ros::L3Cam::loadLidarDefaultParams ( )
private

Definition at line 552 of file l3cam_ros_node.cpp.

◆ loadNetworkDefaultParams()

void l3cam_ros::L3Cam::loadNetworkDefaultParams ( )
private

Definition at line 538 of file l3cam_ros_node.cpp.

◆ loadParam()

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

Definition at line 447 of file l3cam_ros_node.cpp.

◆ loadPolarimetricDefaultParams()

void l3cam_ros::L3Cam::loadPolarimetricDefaultParams ( )
private

Values might not coincide when enabling polarimetric_auto_gain

Values might not coincide when disabling polarimetric_auto_gain

Values might not coincide when enabling polarimetric_auto_exposure_time

Values might not coincide when disabling polarimetric_auto_exposure_time

Definition at line 607 of file l3cam_ros_node.cpp.

◆ loadRgbDefaultParams()

void l3cam_ros::L3Cam::loadRgbDefaultParams ( )
private

Values might not coincide when disabling rgb_auto_white_balance

Values might not coincide when disabling rgb_auto_exposure_time

Definition at line 665 of file l3cam_ros_node.cpp.

◆ loadThermalDefaultParams()

void l3cam_ros::L3Cam::loadThermalDefaultParams ( )
private

Definition at line 725 of file l3cam_ros_node.cpp.

◆ networkDisconnected()

void l3cam_ros::L3Cam::networkDisconnected ( int  code)
private

Definition at line 2096 of file l3cam_ros_node.cpp.

◆ polDisconnected()

void l3cam_ros::L3Cam::polDisconnected ( int  code)
private

Definition at line 2122 of file l3cam_ros_node.cpp.

◆ powerOffDevice()

bool l3cam_ros::L3Cam::powerOffDevice ( l3cam_ros::PowerOffDevice::Request &  req,
l3cam_ros::PowerOffDevice::Response &  res 
)
private

Definition at line 1174 of file l3cam_ros_node.cpp.

◆ printDefaultError()

void l3cam_ros::L3Cam::printDefaultError ( int  error,
std::string  param 
)
inlineprivate

Definition at line 436 of file l3cam_ros_node.cpp.

◆ rgbDisconnected()

void l3cam_ros::L3Cam::rgbDisconnected ( int  code)
private

Definition at line 2139 of file l3cam_ros_node.cpp.

◆ setBiasShortRange()

bool l3cam_ros::L3Cam::setBiasShortRange ( l3cam_ros::SetBiasShortRange::Request &  req,
l3cam_ros::SetBiasShortRange::Response &  res 
)
private

Definition at line 1290 of file l3cam_ros_node.cpp.

◆ setPolarimetricCameraDefaultSettings()

bool l3cam_ros::L3Cam::setPolarimetricCameraDefaultSettings ( l3cam_ros::SetPolarimetricCameraDefaultSettings::Request &  req,
l3cam_ros::SetPolarimetricCameraDefaultSettings::Response &  res 
)
private

Definition at line 1323 of file l3cam_ros_node.cpp.

◆ setRgbCameraDefaultSettings()

bool l3cam_ros::L3Cam::setRgbCameraDefaultSettings ( l3cam_ros::SetRgbCameraDefaultSettings::Request &  req,
l3cam_ros::SetRgbCameraDefaultSettings::Response &  res 
)
private

Definition at line 1379 of file l3cam_ros_node.cpp.

◆ spin()

void l3cam_ros::L3Cam::spin ( )

Definition at line 60 of file l3cam_ros_node.cpp.

◆ startDevice()

bool l3cam_ros::L3Cam::startDevice ( l3cam_ros::StartDevice::Request &  req,
l3cam_ros::StartDevice::Response &  res 
)
private

Definition at line 1182 of file l3cam_ros_node.cpp.

◆ startDeviceStream()

int l3cam_ros::L3Cam::startDeviceStream ( )

Definition at line 173 of file l3cam_ros_node.cpp.

◆ startStream()

bool l3cam_ros::L3Cam::startStream ( l3cam_ros::StartStream::Request &  req,
l3cam_ros::StartStream::Response &  res 
)
private

Definition at line 1209 of file l3cam_ros_node.cpp.

◆ stopDevice()

bool l3cam_ros::L3Cam::stopDevice ( l3cam_ros::StopDevice::Request &  req,
l3cam_ros::StopDevice::Response &  res 
)
private

Definition at line 1193 of file l3cam_ros_node.cpp.

◆ stopStream()

bool l3cam_ros::L3Cam::stopStream ( l3cam_ros::StopStream::Request &  req,
l3cam_ros::StopStream::Response &  res 
)
private

Definition at line 1220 of file l3cam_ros_node.cpp.

◆ terminate()

bool l3cam_ros::L3Cam::terminate ( l3cam_ros::Terminate::Request &  req,
l3cam_ros::Terminate::Response &  res 
)
private

Definition at line 980 of file l3cam_ros_node.cpp.

◆ thermalDisconnected()

void l3cam_ros::L3Cam::thermalDisconnected ( int  code)
private

Definition at line 2156 of file l3cam_ros_node.cpp.

Member Data Documentation

◆ client_lidar_configuration_disconnected_

ros::ServiceClient l3cam_ros::L3Cam::client_lidar_configuration_disconnected_
private

Definition at line 374 of file l3cam_ros_node.hpp.

◆ client_lidar_stream_disconnected_

ros::ServiceClient l3cam_ros::L3Cam::client_lidar_stream_disconnected_
private

Definition at line 372 of file l3cam_ros_node.hpp.

◆ client_narrow_configuration_disconnected_

ros::ServiceClient l3cam_ros::L3Cam::client_narrow_configuration_disconnected_
private

Definition at line 390 of file l3cam_ros_node.hpp.

◆ client_network_disconnected_

ros::ServiceClient l3cam_ros::L3Cam::client_network_disconnected_
private

Definition at line 370 of file l3cam_ros_node.hpp.

◆ client_pol_configuration_disconnected_

ros::ServiceClient l3cam_ros::L3Cam::client_pol_configuration_disconnected_
private

Definition at line 378 of file l3cam_ros_node.hpp.

◆ client_pol_wide_stream_disconnected_

ros::ServiceClient l3cam_ros::L3Cam::client_pol_wide_stream_disconnected_
private

Definition at line 376 of file l3cam_ros_node.hpp.

◆ client_rgb_configuration_disconnected_

ros::ServiceClient l3cam_ros::L3Cam::client_rgb_configuration_disconnected_
private

Definition at line 382 of file l3cam_ros_node.hpp.

◆ client_rgb_narrow_stream_disconnected_

ros::ServiceClient l3cam_ros::L3Cam::client_rgb_narrow_stream_disconnected_
private

Definition at line 380 of file l3cam_ros_node.hpp.

◆ client_thermal_configuration_disconnected_

ros::ServiceClient l3cam_ros::L3Cam::client_thermal_configuration_disconnected_
private

Definition at line 386 of file l3cam_ros_node.hpp.

◆ client_thermal_stream_disconnected_

ros::ServiceClient l3cam_ros::L3Cam::client_thermal_stream_disconnected_
private

Definition at line 384 of file l3cam_ros_node.hpp.

◆ client_wide_configuration_disconnected_

ros::ServiceClient l3cam_ros::L3Cam::client_wide_configuration_disconnected_
private

Definition at line 388 of file l3cam_ros_node.hpp.

◆ m_allied_narrow_sensor

sensor* l3cam_ros::L3Cam::m_allied_narrow_sensor = NULL
private

Definition at line 401 of file l3cam_ros_node.hpp.

◆ m_allied_wide_sensor

sensor* l3cam_ros::L3Cam::m_allied_wide_sensor = NULL
private

Definition at line 400 of file l3cam_ros_node.hpp.

◆ m_av_sensors

sensor l3cam_ros::L3Cam::m_av_sensors[6]
private

Definition at line 393 of file l3cam_ros_node.hpp.

◆ m_devices

l3cam l3cam_ros::L3Cam::m_devices[1]

Definition at line 146 of file l3cam_ros_node.hpp.

◆ m_econ_wide_sensor

sensor* l3cam_ros::L3Cam::m_econ_wide_sensor = NULL
private

Definition at line 397 of file l3cam_ros_node.hpp.

◆ m_lidar_sensor

sensor* l3cam_ros::L3Cam::m_lidar_sensor = NULL
private

Definition at line 395 of file l3cam_ros_node.hpp.

◆ m_num_devices

int l3cam_ros::L3Cam::m_num_devices
private

Definition at line 403 of file l3cam_ros_node.hpp.

◆ m_polarimetric_sensor

sensor* l3cam_ros::L3Cam::m_polarimetric_sensor = NULL
private

Definition at line 399 of file l3cam_ros_node.hpp.

◆ m_rgb_sensor

sensor* l3cam_ros::L3Cam::m_rgb_sensor = NULL
private

Definition at line 396 of file l3cam_ros_node.hpp.

◆ m_shutdown_requested

bool l3cam_ros::L3Cam::m_shutdown_requested
private

Definition at line 406 of file l3cam_ros_node.hpp.

◆ m_status

LibL3CamStatus l3cam_ros::L3Cam::m_status

Definition at line 147 of file l3cam_ros_node.hpp.

◆ m_thermal_sensor

sensor* l3cam_ros::L3Cam::m_thermal_sensor = NULL
private

Definition at line 398 of file l3cam_ros_node.hpp.

◆ srv_change_allied_auto_exposure_time_range_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_allied_auto_exposure_time_range_
private

Definition at line 332 of file l3cam_ros_node.hpp.

◆ srv_change_allied_auto_gain_range_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_allied_auto_gain_range_
private

Definition at line 335 of file l3cam_ros_node.hpp.

◆ srv_change_allied_balance_ratio_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_allied_balance_ratio_
private

Definition at line 342 of file l3cam_ros_node.hpp.

◆ srv_change_allied_balance_ratio_selector_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_allied_balance_ratio_selector_
private

Definition at line 341 of file l3cam_ros_node.hpp.

◆ srv_change_allied_balance_white_auto_rate_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_allied_balance_white_auto_rate_
private

Definition at line 343 of file l3cam_ros_node.hpp.

◆ srv_change_allied_balance_white_auto_tolerance_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_allied_balance_white_auto_tolerance_
private

Definition at line 344 of file l3cam_ros_node.hpp.

◆ srv_change_allied_exposure_time_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_allied_exposure_time_
private

Definition at line 330 of file l3cam_ros_node.hpp.

◆ srv_change_allied_gain_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_allied_gain_
private

Definition at line 333 of file l3cam_ros_node.hpp.

◆ srv_change_allied_gamma_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_allied_gamma_
private

Definition at line 336 of file l3cam_ros_node.hpp.

◆ srv_change_allied_hue_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_allied_hue_
private

Definition at line 338 of file l3cam_ros_node.hpp.

◆ srv_change_allied_intensity_auto_precedence_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_allied_intensity_auto_precedence_
private

Definition at line 339 of file l3cam_ros_node.hpp.

◆ srv_change_allied_intensity_controller_region_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_allied_intensity_controller_region_
private

Definition at line 345 of file l3cam_ros_node.hpp.

◆ srv_change_allied_intensity_controller_target_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_allied_intensity_controller_target_
private

Definition at line 346 of file l3cam_ros_node.hpp.

◆ srv_change_allied_saturation_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_allied_saturation_
private

Definition at line 337 of file l3cam_ros_node.hpp.

◆ srv_change_autobias_value_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_autobias_value_
private

Definition at line 299 of file l3cam_ros_node.hpp.

◆ srv_change_bias_value_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_bias_value_
private

Definition at line 298 of file l3cam_ros_node.hpp.

◆ srv_change_distance_range_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_distance_range_
private

Definition at line 295 of file l3cam_ros_node.hpp.

◆ srv_change_network_configuration_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_network_configuration_
private

Definition at line 285 of file l3cam_ros_node.hpp.

◆ srv_change_pointcloud_color_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_pointcloud_color_
private

Definition at line 293 of file l3cam_ros_node.hpp.

◆ srv_change_pointcloud_color_range_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_pointcloud_color_range_
private

Definition at line 294 of file l3cam_ros_node.hpp.

◆ srv_change_polarimetric_auto_exposure_time_range_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_polarimetric_auto_exposure_time_range_
private

Definition at line 309 of file l3cam_ros_node.hpp.

◆ srv_change_polarimetric_auto_gain_range_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_polarimetric_auto_gain_range_
private

Definition at line 306 of file l3cam_ros_node.hpp.

◆ srv_change_polarimetric_black_level_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_polarimetric_black_level_
private

Definition at line 304 of file l3cam_ros_node.hpp.

◆ srv_change_polarimetric_brightness_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_polarimetric_brightness_
private

Definition at line 303 of file l3cam_ros_node.hpp.

◆ srv_change_polarimetric_exposure_time_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_polarimetric_exposure_time_
private

Definition at line 310 of file l3cam_ros_node.hpp.

◆ srv_change_polarimetric_gain_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_polarimetric_gain_
private

Definition at line 307 of file l3cam_ros_node.hpp.

◆ srv_change_rgb_brightness_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_rgb_brightness_
private

Definition at line 313 of file l3cam_ros_node.hpp.

◆ srv_change_rgb_contrast_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_rgb_contrast_
private

Definition at line 314 of file l3cam_ros_node.hpp.

◆ srv_change_rgb_exposure_time_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_rgb_exposure_time_
private

Definition at line 322 of file l3cam_ros_node.hpp.

◆ srv_change_rgb_gain_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_rgb_gain_
private

Definition at line 318 of file l3cam_ros_node.hpp.

◆ srv_change_rgb_gamma_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_rgb_gamma_
private

Definition at line 317 of file l3cam_ros_node.hpp.

◆ srv_change_rgb_saturation_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_rgb_saturation_
private

Definition at line 315 of file l3cam_ros_node.hpp.

◆ srv_change_rgb_sharpness_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_rgb_sharpness_
private

Definition at line 316 of file l3cam_ros_node.hpp.

◆ srv_change_rgb_white_balance_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_rgb_white_balance_
private

Definition at line 320 of file l3cam_ros_node.hpp.

◆ srv_change_streaming_protocol_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_streaming_protocol_
private

Definition at line 282 of file l3cam_ros_node.hpp.

◆ srv_change_thermal_colormap_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_thermal_colormap_
private

Definition at line 324 of file l3cam_ros_node.hpp.

◆ srv_change_thermal_processing_pipeline_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_thermal_processing_pipeline_
private

Definition at line 327 of file l3cam_ros_node.hpp.

◆ srv_change_thermal_temperature_filter_

ros::ServiceServer l3cam_ros::L3Cam::srv_change_thermal_temperature_filter_
private

Definition at line 326 of file l3cam_ros_node.hpp.

◆ srv_enable_allied_auto_exposure_time_

ros::ServiceServer l3cam_ros::L3Cam::srv_enable_allied_auto_exposure_time_
private

Definition at line 331 of file l3cam_ros_node.hpp.

◆ srv_enable_allied_auto_gain_

ros::ServiceServer l3cam_ros::L3Cam::srv_enable_allied_auto_gain_
private

Definition at line 334 of file l3cam_ros_node.hpp.

◆ srv_enable_allied_auto_white_balance_

ros::ServiceServer l3cam_ros::L3Cam::srv_enable_allied_auto_white_balance_
private

Definition at line 340 of file l3cam_ros_node.hpp.

◆ srv_enable_auto_bias_

ros::ServiceServer l3cam_ros::L3Cam::srv_enable_auto_bias_
private

Definition at line 297 of file l3cam_ros_node.hpp.

◆ srv_enable_polarimetric_auto_exposure_time_

ros::ServiceServer l3cam_ros::L3Cam::srv_enable_polarimetric_auto_exposure_time_
private

Definition at line 308 of file l3cam_ros_node.hpp.

◆ srv_enable_polarimetric_auto_gain_

ros::ServiceServer l3cam_ros::L3Cam::srv_enable_polarimetric_auto_gain_
private

Definition at line 305 of file l3cam_ros_node.hpp.

◆ srv_enable_rgb_auto_exposure_time_

ros::ServiceServer l3cam_ros::L3Cam::srv_enable_rgb_auto_exposure_time_
private

Definition at line 321 of file l3cam_ros_node.hpp.

◆ srv_enable_rgb_auto_white_balance_

ros::ServiceServer l3cam_ros::L3Cam::srv_enable_rgb_auto_white_balance_
private

Definition at line 319 of file l3cam_ros_node.hpp.

◆ srv_enable_thermal_temperature_data_udp_

ros::ServiceServer l3cam_ros::L3Cam::srv_enable_thermal_temperature_data_udp_
private

Definition at line 328 of file l3cam_ros_node.hpp.

◆ srv_enable_thermal_temperature_filter_

ros::ServiceServer l3cam_ros::L3Cam::srv_enable_thermal_temperature_filter_
private

Definition at line 325 of file l3cam_ros_node.hpp.

◆ srv_find_devices_

ros::ServiceServer l3cam_ros::L3Cam::srv_find_devices_
private

Definition at line 277 of file l3cam_ros_node.hpp.

◆ srv_get_allied_auto_exposure_time_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_auto_exposure_time_
private

Definition at line 350 of file l3cam_ros_node.hpp.

◆ srv_get_allied_auto_exposure_time_range_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_auto_exposure_time_range_
private

Definition at line 351 of file l3cam_ros_node.hpp.

◆ srv_get_allied_auto_gain_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_auto_gain_
private

Definition at line 353 of file l3cam_ros_node.hpp.

◆ srv_get_allied_auto_gain_range_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_auto_gain_range_
private

Definition at line 354 of file l3cam_ros_node.hpp.

◆ srv_get_allied_auto_mode_region_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_auto_mode_region_
private

Definition at line 365 of file l3cam_ros_node.hpp.

◆ srv_get_allied_auto_white_balance_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_auto_white_balance_
private

Definition at line 360 of file l3cam_ros_node.hpp.

◆ srv_get_allied_balance_ratio_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_balance_ratio_
private

Definition at line 362 of file l3cam_ros_node.hpp.

◆ srv_get_allied_balance_ratio_selector_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_balance_ratio_selector_
private

Definition at line 361 of file l3cam_ros_node.hpp.

◆ srv_get_allied_balance_white_auto_rate_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_balance_white_auto_rate_
private

Definition at line 363 of file l3cam_ros_node.hpp.

◆ srv_get_allied_balance_white_auto_tolerance_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_balance_white_auto_tolerance_
private

Definition at line 364 of file l3cam_ros_node.hpp.

◆ srv_get_allied_black_level_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_black_level_
private

Definition at line 348 of file l3cam_ros_node.hpp.

◆ srv_get_allied_exposure_time_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_exposure_time_
private

Definition at line 349 of file l3cam_ros_node.hpp.

◆ srv_get_allied_gain_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_gain_
private

Definition at line 352 of file l3cam_ros_node.hpp.

◆ srv_get_allied_gamma_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_gamma_
private

Definition at line 355 of file l3cam_ros_node.hpp.

◆ srv_get_allied_hue_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_hue_
private

Definition at line 358 of file l3cam_ros_node.hpp.

◆ srv_get_allied_intensity_auto_precedence_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_intensity_auto_precedence_
private

Definition at line 359 of file l3cam_ros_node.hpp.

◆ srv_get_allied_intensity_controller_region_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_intensity_controller_region_
private

Definition at line 366 of file l3cam_ros_node.hpp.

◆ srv_get_allied_intensity_controller_target_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_intensity_controller_target_
private

Definition at line 367 of file l3cam_ros_node.hpp.

◆ srv_get_allied_max_driver_buffers_count_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_max_driver_buffers_count_
private

Definition at line 368 of file l3cam_ros_node.hpp.

◆ srv_get_allied_saturation_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_saturation_
private

Definition at line 356 of file l3cam_ros_node.hpp.

◆ srv_get_allied_sharpness_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_allied_sharpness_
private

Definition at line 357 of file l3cam_ros_node.hpp.

◆ srv_get_autobias_value_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_autobias_value_
private

Definition at line 300 of file l3cam_ros_node.hpp.

◆ srv_get_device_info_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_device_info_
private

Definition at line 279 of file l3cam_ros_node.hpp.

◆ srv_get_device_status_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_device_status_
private

Definition at line 280 of file l3cam_ros_node.hpp.

◆ srv_get_device_temperatures_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_device_temperatures_
private

Definition at line 291 of file l3cam_ros_node.hpp.

◆ srv_get_local_server_address_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_local_server_address_
private

Definition at line 278 of file l3cam_ros_node.hpp.

◆ srv_get_network_configuration_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_network_configuration_
private

Definition at line 284 of file l3cam_ros_node.hpp.

◆ srv_get_rtsp_pipeline_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_rtsp_pipeline_
private

Definition at line 283 of file l3cam_ros_node.hpp.

◆ srv_get_sensors_available_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_sensors_available_
private

Definition at line 281 of file l3cam_ros_node.hpp.

◆ srv_get_version_

ros::ServiceServer l3cam_ros::L3Cam::srv_get_version_
private

Definition at line 274 of file l3cam_ros_node.hpp.

◆ srv_initialize_

ros::ServiceServer l3cam_ros::L3Cam::srv_initialize_
private

Definition at line 275 of file l3cam_ros_node.hpp.

◆ srv_libl3cam_status_

ros::ServiceServer l3cam_ros::L3Cam::srv_libl3cam_status_
private

Definition at line 273 of file l3cam_ros_node.hpp.

◆ srv_narrow_configuration_disconnected_

l3cam_ros::SensorDisconnected l3cam_ros::L3Cam::srv_narrow_configuration_disconnected_
private

Definition at line 391 of file l3cam_ros_node.hpp.

◆ srv_network_disconnected_

l3cam_ros::SensorDisconnected l3cam_ros::L3Cam::srv_network_disconnected_
private

Definition at line 371 of file l3cam_ros_node.hpp.

◆ srv_pointcloud_configuration_disconnected_

l3cam_ros::SensorDisconnected l3cam_ros::L3Cam::srv_pointcloud_configuration_disconnected_
private

Definition at line 375 of file l3cam_ros_node.hpp.

◆ srv_pointcloud_stream_disconnected_

l3cam_ros::SensorDisconnected l3cam_ros::L3Cam::srv_pointcloud_stream_disconnected_
private

Definition at line 373 of file l3cam_ros_node.hpp.

◆ srv_pol_configuration_disconnected_

l3cam_ros::SensorDisconnected l3cam_ros::L3Cam::srv_pol_configuration_disconnected_
private

Definition at line 379 of file l3cam_ros_node.hpp.

◆ srv_pol_wide_stream_disconnected_

l3cam_ros::SensorDisconnected l3cam_ros::L3Cam::srv_pol_wide_stream_disconnected_
private

Definition at line 377 of file l3cam_ros_node.hpp.

◆ srv_power_off_device_

ros::ServiceServer l3cam_ros::L3Cam::srv_power_off_device_
private

Definition at line 286 of file l3cam_ros_node.hpp.

◆ srv_rgb_configuration_disconnected_

l3cam_ros::SensorDisconnected l3cam_ros::L3Cam::srv_rgb_configuration_disconnected_
private

Definition at line 383 of file l3cam_ros_node.hpp.

◆ srv_rgb_narrow_stream_disconnected_

l3cam_ros::SensorDisconnected l3cam_ros::L3Cam::srv_rgb_narrow_stream_disconnected_
private

Definition at line 381 of file l3cam_ros_node.hpp.

◆ srv_set_bias_short_range_

ros::ServiceServer l3cam_ros::L3Cam::srv_set_bias_short_range_
private

Definition at line 296 of file l3cam_ros_node.hpp.

◆ srv_set_polarimetric_default_settings_

ros::ServiceServer l3cam_ros::L3Cam::srv_set_polarimetric_default_settings_
private

Definition at line 302 of file l3cam_ros_node.hpp.

◆ srv_set_rgb_default_settings_

ros::ServiceServer l3cam_ros::L3Cam::srv_set_rgb_default_settings_
private

Definition at line 312 of file l3cam_ros_node.hpp.

◆ srv_start_device_

ros::ServiceServer l3cam_ros::L3Cam::srv_start_device_
private

Definition at line 287 of file l3cam_ros_node.hpp.

◆ srv_start_stream_

ros::ServiceServer l3cam_ros::L3Cam::srv_start_stream_
private

Definition at line 289 of file l3cam_ros_node.hpp.

◆ srv_stop_device_

ros::ServiceServer l3cam_ros::L3Cam::srv_stop_device_
private

Definition at line 288 of file l3cam_ros_node.hpp.

◆ srv_stop_stream_

ros::ServiceServer l3cam_ros::L3Cam::srv_stop_stream_
private

Definition at line 290 of file l3cam_ros_node.hpp.

◆ srv_terminate_

ros::ServiceServer l3cam_ros::L3Cam::srv_terminate_
private

Definition at line 276 of file l3cam_ros_node.hpp.

◆ srv_thermal_configuration_disconnected_

l3cam_ros::SensorDisconnected l3cam_ros::L3Cam::srv_thermal_configuration_disconnected_
private

Definition at line 387 of file l3cam_ros_node.hpp.

◆ srv_thermal_stream_disconnected_

l3cam_ros::SensorDisconnected l3cam_ros::L3Cam::srv_thermal_stream_disconnected_
private

Definition at line 385 of file l3cam_ros_node.hpp.

◆ srv_wide_configuration_disconnected_

l3cam_ros::SensorDisconnected l3cam_ros::L3Cam::srv_wide_configuration_disconnected_
private

Definition at line 389 of file l3cam_ros_node.hpp.

◆ timeout_secs_

int l3cam_ros::L3Cam::timeout_secs_
private

Definition at line 404 of file l3cam_ros_node.hpp.


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


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