Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #ifndef _PHIDGETIKROS_H_
00019 #define _PHIDGETIKROS_H_
00020
00021 #include <ros/ros.h>
00022 #include <cob_phidgets/phidgetik.h>
00023 #include <cob_phidgets/SetDataRate.h>
00024 #include <cob_phidgets/SetDigitalSensor.h>
00025 #include <cob_phidgets/SetTriggerValue.h>
00026 #include <cob_phidgets/DigitalSensor.h>
00027 #include <cob_phidgets/AnalogSensor.h>
00028
00029 #include <thread>
00030 #include <mutex>
00031 #include <map>
00032
00033 class PhidgetIKROS: public PhidgetIK
00034 {
00035 public:
00036 PhidgetIKROS(ros::NodeHandle nh, int serial_num, std::string board_name, XmlRpc::XmlRpcValue* sensor_params, SensingMode mode);
00037 ~PhidgetIKROS();
00038
00039 private:
00040 ros::NodeHandle _nh;
00041 ros::Publisher _pubAnalog;
00042 ros::Publisher _pubDigital;
00043 ros::Subscriber _subDigital;
00044 ros::ServiceServer _srvDigitalOut;
00045 ros::ServiceServer _srvDataRate;
00046 ros::ServiceServer _srvTriggerValue;
00047
00048 int _serial_num;
00049 std::string _board_name;
00050
00051 struct OutputCompare
00052 {
00053 bool updated;
00054 int index;
00055 int state;
00056 };
00057
00058 OutputCompare _outputChanged;
00059 std::mutex _mutex;
00060
00061 std::map<int, std::string> _indexNameMapAnalog;
00062 std::map<std::string, int> _indexNameMapAnalogRev;
00063 std::map<int, std::string> _indexNameMapDigitalIn;
00064 std::map<std::string, int> _indexNameMapDigitalInRev;
00065 std::map<int, std::string> _indexNameMapDigitalOut;
00066 std::map<std::string, int> _indexNameMapDigitalOutRev;
00067 std::map<int, std::string>::iterator _indexNameMapItr;
00068 std::map<std::string, int>::iterator _indexNameMapRevItr;
00069
00070 auto readParams(XmlRpc::XmlRpcValue* sensor_params) -> void;
00071
00072 auto update() -> void;
00073
00074 auto attachHandler() -> int;
00075 auto detachHandler() -> int;
00076
00077 auto inputChangeHandler(int index, int inputState) -> int;
00078 auto outputChangeHandler(int index, int outputState) -> int;
00079 auto sensorChangeHandler(int index, int sensorValue) -> int;
00080
00081 auto onDigitalOutCallback(const cob_phidgets::DigitalSensorConstPtr& msg) -> void;
00082 auto setDigitalOutCallback(cob_phidgets::SetDigitalSensor::Request &req,
00083 cob_phidgets::SetDigitalSensor::Response &res) -> bool;
00084 auto setDataRateCallback(cob_phidgets::SetDataRate::Request &req,
00085 cob_phidgets::SetDataRate::Response &res) -> bool;
00086 auto setTriggerValueCallback(cob_phidgets::SetTriggerValue::Request &req,
00087 cob_phidgets::SetTriggerValue::Response &res) -> bool;
00088 };
00089 #endif //_PHIDGETIK_H_