18 #ifndef _PHIDGETIKROS_H_ 19 #define _PHIDGETIKROS_H_ 23 #include <cob_phidgets/SetDataRate.h> 24 #include <cob_phidgets/SetDigitalSensor.h> 25 #include <cob_phidgets/SetTriggerValue.h> 26 #include <cob_phidgets/DigitalSensor.h> 27 #include <cob_phidgets/AnalogSensor.h> 83 cob_phidgets::SetDigitalSensor::Response &res) -> bool;
85 cob_phidgets::SetDataRate::Response &res) -> bool;
87 cob_phidgets::SetTriggerValue::Response &res) -> bool;
89 #endif //_PHIDGETIK_H_ auto readParams(XmlRpc::XmlRpcValue *sensor_params) -> void
std::map< int, std::string > _indexNameMapDigitalOut
std::map< std::string, int > _indexNameMapAnalogRev
auto inputChangeHandler(int index, int inputState) -> int
ros::Subscriber _subDigital
auto setDigitalOutCallback(cob_phidgets::SetDigitalSensor::Request &req, cob_phidgets::SetDigitalSensor::Response &res) -> bool
OutputCompare _outputChanged
ros::ServiceServer _srvTriggerValue
ros::Publisher _pubAnalog
auto detachHandler() -> int
auto sensorChangeHandler(int index, int sensorValue) -> int
std::map< std::string, int > _indexNameMapDigitalInRev
auto setDataRateCallback(cob_phidgets::SetDataRate::Request &req, cob_phidgets::SetDataRate::Response &res) -> bool
std::map< int, std::string >::iterator _indexNameMapItr
std::map< std::string, int > _indexNameMapDigitalOutRev
auto outputChangeHandler(int index, int outputState) -> int
auto onDigitalOutCallback(const cob_phidgets::DigitalSensorConstPtr &msg) -> void
ros::Publisher _pubDigital
ros::ServiceServer _srvDataRate
auto attachHandler() -> int
std::map< int, std::string > _indexNameMapDigitalIn
ros::ServiceServer _srvDigitalOut
auto setTriggerValueCallback(cob_phidgets::SetTriggerValue::Request &req, cob_phidgets::SetTriggerValue::Response &res) -> bool
PhidgetIKROS(ros::NodeHandle nh, int serial_num, std::string board_name, XmlRpc::XmlRpcValue *sensor_params, SensingMode mode)
std::map< int, std::string > _indexNameMapAnalog
std::map< std::string, int >::iterator _indexNameMapRevItr