phidgetik_ros.h
Go to the documentation of this file.
00001 
00060 #ifndef _PHIDGETIKROS_H_
00061 #define _PHIDGETIKROS_H_
00062 
00063 #include <ros/ros.h>
00064 #include <cob_phidgets/phidgetik.h>
00065 #include <cob_phidgets/SetDataRate.h>
00066 #include <cob_phidgets/SetDigitalSensor.h>
00067 #include <cob_phidgets/SetTriggerValue.h>
00068 #include <cob_phidgets/DigitalSensor.h>
00069 #include <cob_phidgets/AnalogSensor.h>
00070 
00071 #include <thread>
00072 #include <mutex>
00073 #include <map>
00074 
00075 class PhidgetIKROS: public PhidgetIK
00076 {
00077 public:
00078         PhidgetIKROS(ros::NodeHandle nh, int serial_num, std::string board_name, XmlRpc::XmlRpcValue* sensor_params, SensingMode mode);
00079         ~PhidgetIKROS();
00080 
00081 private:
00082         ros::NodeHandle _nh;
00083         ros::Publisher _pubAnalog;
00084         ros::Publisher _pubDigital;
00085         ros::Subscriber _subDigital;
00086         ros::ServiceServer _srvDigitalOut;
00087         ros::ServiceServer _srvDataRate;
00088         ros::ServiceServer _srvTriggerValue;
00089 
00090         int _serial_num;
00091 
00092         struct OutputCompare
00093         {
00094                 bool updated;
00095                 int index;
00096                 int state;
00097         };
00098 
00099         OutputCompare _outputChanged;
00100         std::mutex _mutex;
00101 
00102         std::map<int, std::string> _indexNameMapAnalog;
00103         std::map<std::string, int> _indexNameMapAnalogRev;
00104         std::map<int, std::string> _indexNameMapDigitalIn;
00105         std::map<std::string, int> _indexNameMapDigitalInRev;
00106         std::map<int, std::string> _indexNameMapDigitalOut;
00107         std::map<std::string, int> _indexNameMapDigitalOutRev;
00108         std::map<int, std::string>::iterator _indexNameMapItr;
00109         std::map<std::string, int>::iterator _indexNameMapRevItr;
00110 
00111         auto readParams(XmlRpc::XmlRpcValue* sensor_params) -> void;
00112 
00113         auto update() -> void;
00114 
00115         auto attachHandler() -> int;
00116         auto detachHandler() -> int;
00117 
00118         auto inputChangeHandler(int index, int inputState) -> int;
00119         auto outputChangeHandler(int index, int outputState) -> int;
00120         auto sensorChangeHandler(int index, int sensorValue) -> int;
00121 
00122         auto onDigitalOutCallback(const cob_phidgets::DigitalSensorConstPtr& msg) -> void;
00123         auto setDigitalOutCallback(cob_phidgets::SetDigitalSensor::Request &req,
00124                                                                                 cob_phidgets::SetDigitalSensor::Response &res) -> bool;
00125         auto setDataRateCallback(cob_phidgets::SetDataRate::Request &req,
00126                                                                                 cob_phidgets::SetDataRate::Response &res) -> bool;
00127         auto setTriggerValueCallback(cob_phidgets::SetTriggerValue::Request &req,
00128                                                                                 cob_phidgets::SetTriggerValue::Response &res) -> bool;
00129 };
00130 #endif //_PHIDGETIK_H_


cob_phidgets
Author(s): Florian Weisshardt, Benjamin Maidel
autogenerated on Sun Oct 5 2014 23:10:20