#include <phidgetik_ros.h>
Classes | |
struct | OutputCompare |
Public Member Functions | |
PhidgetIKROS (ros::NodeHandle nh, int serial_num, std::string board_name, XmlRpc::XmlRpcValue *sensor_params, SensingMode mode) | |
~PhidgetIKROS () | |
Public Member Functions inherited from PhidgetIK | |
auto | getDataRate (int index) -> int |
auto | getDataRateMax (int index) -> int |
auto | getDataRateMin (int index) -> int |
auto | getError () -> int |
auto | getInputCount () -> int |
auto | getInputState (int index) -> int |
auto | getOutputCount () -> int |
auto | getOutputState (int index) -> int |
auto | getRatiometric () -> int |
auto | getSensorChangeTrigger (int index) -> int |
auto | getSensorCount () -> int |
auto | getSensorRawValue (int index) -> int |
auto | getSensorValue (int index) -> int |
auto | init (int serial_number) -> int |
PhidgetIK (SensingMode mode) | |
auto | setDataRate (int index, int datarate) -> int |
auto | setOutputState (int index, int state) -> int |
auto | setRatiometric (int ratiometric) -> int |
auto | setSensorChangeTrigger (int index, int trigger) -> int |
~PhidgetIK () | |
Public Member Functions inherited from Phidget | |
auto | close (int serial_number) -> int |
auto | getDeviceLabel () -> std::string |
auto | getDeviceName () -> std::string |
auto | getDeviceSerialNumber () -> int |
auto | getDeviceType () -> std::string |
auto | getDeviceVersion () -> int |
auto | getLibraryVersion () -> std::string |
auto | open (int serial_number) -> int |
auto | waitForAttachment (int timeout) -> int |
~Phidget () | |
Private Member Functions | |
auto | attachHandler () -> int |
auto | detachHandler () -> int |
auto | inputChangeHandler (int index, int inputState) -> int |
auto | onDigitalOutCallback (const cob_phidgets::DigitalSensorConstPtr &msg) -> void |
auto | outputChangeHandler (int index, int outputState) -> int |
auto | readParams (XmlRpc::XmlRpcValue *sensor_params) -> void |
auto | sensorChangeHandler (int index, int sensorValue) -> int |
auto | setDataRateCallback (cob_phidgets::SetDataRate::Request &req, cob_phidgets::SetDataRate::Response &res) -> bool |
auto | setDigitalOutCallback (cob_phidgets::SetDigitalSensor::Request &req, cob_phidgets::SetDigitalSensor::Response &res) -> bool |
auto | setTriggerValueCallback (cob_phidgets::SetTriggerValue::Request &req, cob_phidgets::SetTriggerValue::Response &res) -> bool |
auto | update () -> void |
Private Attributes | |
std::string | _board_name |
std::map< int, std::string > | _indexNameMapAnalog |
std::map< std::string, int > | _indexNameMapAnalogRev |
std::map< int, std::string > | _indexNameMapDigitalIn |
std::map< std::string, int > | _indexNameMapDigitalInRev |
std::map< int, std::string > | _indexNameMapDigitalOut |
std::map< std::string, int > | _indexNameMapDigitalOutRev |
std::map< int, std::string >::iterator | _indexNameMapItr |
std::map< std::string, int >::iterator | _indexNameMapRevItr |
std::mutex | _mutex |
ros::NodeHandle | _nh |
OutputCompare | _outputChanged |
ros::Publisher | _pubAnalog |
ros::Publisher | _pubDigital |
int | _serial_num |
ros::ServiceServer | _srvDataRate |
ros::ServiceServer | _srvDigitalOut |
ros::ServiceServer | _srvTriggerValue |
ros::Subscriber | _subDigital |
Additional Inherited Members | |
Public Types inherited from Phidget | |
enum | SensingMode { SensingMode::EVENT =0, SensingMode::POLLING =1 } |
Static Public Member Functions inherited from Phidget | |
static auto | getErrorDescription (int errorCode) -> std::string |
Protected Member Functions inherited from Phidget | |
Phidget (CPhidgetHandle *handle, SensingMode mode) | |
Protected Attributes inherited from PhidgetIK | |
CPhidgetInterfaceKitHandle | _iKitHandle |
Protected Attributes inherited from Phidget | |
int | _last_error |
CPhidgetHandle * | _phiHandle |
SensingMode | _sensMode |
int | _serialNumber |
Definition at line 33 of file phidgetik_ros.h.
PhidgetIKROS::PhidgetIKROS | ( | ros::NodeHandle | nh, |
int | serial_num, | ||
std::string | board_name, | ||
XmlRpc::XmlRpcValue * | sensor_params, | ||
SensingMode | mode | ||
) |
Definition at line 20 of file phidgetik_ros.cpp.
PhidgetIKROS::~PhidgetIKROS | ( | ) |
Definition at line 48 of file phidgetik_ros.cpp.
|
privatevirtual |
Reimplemented from PhidgetIK.
Definition at line 380 of file phidgetik_ros.cpp.
|
privatevirtual |
Reimplemented from PhidgetIK.
Definition at line 416 of file phidgetik_ros.cpp.
|
privatevirtual |
Reimplemented from PhidgetIK.
Definition at line 232 of file phidgetik_ros.cpp.
|
private |
Definition at line 344 of file phidgetik_ros.cpp.
|
privatevirtual |
Reimplemented from PhidgetIK.
Definition at line 254 of file phidgetik_ros.cpp.
|
private |
Definition at line 52 of file phidgetik_ros.cpp.
|
privatevirtual |
Reimplemented from PhidgetIK.
Definition at line 263 of file phidgetik_ros.cpp.
|
private |
Definition at line 367 of file phidgetik_ros.cpp.
|
private |
Definition at line 286 of file phidgetik_ros.cpp.
|
private |
Definition at line 373 of file phidgetik_ros.cpp.
|
privatevirtual |
Reimplemented from PhidgetIK.
Definition at line 168 of file phidgetik_ros.cpp.
|
private |
Definition at line 49 of file phidgetik_ros.h.
|
private |
Definition at line 61 of file phidgetik_ros.h.
|
private |
Definition at line 62 of file phidgetik_ros.h.
|
private |
Definition at line 63 of file phidgetik_ros.h.
|
private |
Definition at line 64 of file phidgetik_ros.h.
|
private |
Definition at line 65 of file phidgetik_ros.h.
|
private |
Definition at line 66 of file phidgetik_ros.h.
|
private |
Definition at line 67 of file phidgetik_ros.h.
|
private |
Definition at line 68 of file phidgetik_ros.h.
|
private |
Definition at line 59 of file phidgetik_ros.h.
|
private |
Definition at line 40 of file phidgetik_ros.h.
|
private |
Definition at line 58 of file phidgetik_ros.h.
|
private |
Definition at line 41 of file phidgetik_ros.h.
|
private |
Definition at line 42 of file phidgetik_ros.h.
|
private |
Definition at line 48 of file phidgetik_ros.h.
|
private |
Definition at line 45 of file phidgetik_ros.h.
|
private |
Definition at line 44 of file phidgetik_ros.h.
|
private |
Definition at line 46 of file phidgetik_ros.h.
|
private |
Definition at line 43 of file phidgetik_ros.h.