Public Member Functions | |
AlliedNarrowConfiguration () | |
void | setDynamicReconfigure () |
void | spin () |
![]() | |
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 |
CallbackQueueInterface * | getCallbackQueue () 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 |
NodeHandle & | operator= (const NodeHandle &rhs) |
T | param (const std::string ¶m_name, const T &default_val) const |
bool | param (const std::string ¶m_name, T ¶m_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 | callAutoExposureTime (l3cam_ros::AlliedNarrowConfig &config) |
int | callAutoExposureTimeRange (l3cam_ros::AlliedNarrowConfig &config) |
int | callAutoGain (l3cam_ros::AlliedNarrowConfig &config) |
int | callAutoGainRange (l3cam_ros::AlliedNarrowConfig &config) |
int | callAutoWhiteBalance (l3cam_ros::AlliedNarrowConfig &config) |
int | callBalanceRatio (l3cam_ros::AlliedNarrowConfig &config) |
int | callBalanceRatioSelector (l3cam_ros::AlliedNarrowConfig &config) |
int | callBalanceWhiteAutoRate (l3cam_ros::AlliedNarrowConfig &config) |
int | callBalanceWhiteAutoTolerance (l3cam_ros::AlliedNarrowConfig &config) |
int | callExposureTime (l3cam_ros::AlliedNarrowConfig &config) |
int | callGain (l3cam_ros::AlliedNarrowConfig &config) |
int | callGamma (l3cam_ros::AlliedNarrowConfig &config) |
int | callHue (l3cam_ros::AlliedNarrowConfig &config) |
int | callIntensityAutoPrecedence (l3cam_ros::AlliedNarrowConfig &config) |
int | callIntensityControllerRegion (l3cam_ros::AlliedNarrowConfig &config) |
int | callIntensityControllerTarget (l3cam_ros::AlliedNarrowConfig &config) |
int | callRtspPipeline (l3cam_ros::AlliedNarrowConfig &config) |
int | callSaturation (l3cam_ros::AlliedNarrowConfig &config) |
int | callStreamingProtocol (l3cam_ros::AlliedNarrowConfig &config) |
void | configureDefault (l3cam_ros::AlliedNarrowConfig &config) |
void | loadDefaultParams () |
template<typename T > | |
void | loadParam (const std::string ¶m_name, T ¶m_var, const T &default_val) |
void | parametersCallback (AlliedNarrowConfig &config, uint32_t level) |
bool | sensorDisconnectedCallback (l3cam_ros::SensorDisconnected::Request &req, l3cam_ros::SensorDisconnected::Response &res) |
Definition at line 67 of file allied_narrow_configuration.cpp.
|
inlineexplicit |
Definition at line 70 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 504 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 555 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 636 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 687 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 850 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 910 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 880 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 940 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 970 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 466 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 598 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 730 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 790 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 820 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 1000 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 1030 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 1090 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 760 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 1060 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 175 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 149 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 131 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 380 of file allied_narrow_configuration.cpp.
|
inlineprivate |
Definition at line 1099 of file allied_narrow_configuration.cpp.
|
inline |
Definition at line 105 of file allied_narrow_configuration.cpp.
|
inline |
Definition at line 113 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1163 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1165 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1164 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1167 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1169 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1168 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1174 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1176 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1175 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1177 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1178 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1162 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1166 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1170 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1172 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1173 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1179 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1180 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1182 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1171 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1181 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1121 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1127 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1141 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1139 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1143 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1145 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1151 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1119 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1125 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1137 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1117 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1123 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1129 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1155 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1157 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1153 of file allied_narrow_configuration.cpp.
ros::ServiceClient l3cam_ros::AlliedNarrowConfiguration::client_get_sensors_ |
Definition at line 124 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1133 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1135 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1147 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1149 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1131 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1184 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1185 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1115 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1122 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1128 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1142 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1140 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1144 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1146 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1152 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1120 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1126 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1138 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1118 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1124 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1130 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1156 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1158 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1154 of file allied_narrow_configuration.cpp.
l3cam_ros::GetSensorsAvailable l3cam_ros::AlliedNarrowConfiguration::srv_get_sensors_ |
Definition at line 125 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1134 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1136 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1148 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1150 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1132 of file allied_narrow_configuration.cpp.
|
private |
Definition at line 1160 of file allied_narrow_configuration.cpp.
int l3cam_ros::AlliedNarrowConfiguration::timeout_secs_ |
Definition at line 127 of file allied_narrow_configuration.cpp.