Classes | Public Member Functions | Private Member Functions | Private Attributes
PhidgetIKROS Class Reference

#include <phidgetik_ros.h>

Inheritance diagram for PhidgetIKROS:
Inheritance graph
[legend]

List of all members.

Classes

struct  OutputCompare

Public Member Functions

 PhidgetIKROS (ros::NodeHandle nh, int serial_num, std::string board_name, XmlRpc::XmlRpcValue *sensor_params, SensingMode mode)
 ~PhidgetIKROS ()

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

Detailed Description

Definition at line 75 of file phidgetik_ros.h.


Constructor & Destructor Documentation

PhidgetIKROS::PhidgetIKROS ( ros::NodeHandle  nh,
int  serial_num,
std::string  board_name,
XmlRpc::XmlRpcValue sensor_params,
SensingMode  mode 
)

Definition at line 62 of file phidgetik_ros.cpp.

Definition at line 90 of file phidgetik_ros.cpp.


Member Function Documentation

auto PhidgetIKROS::attachHandler ( ) [private, virtual]

Reimplemented from PhidgetIK.

Definition at line 412 of file phidgetik_ros.cpp.

auto PhidgetIKROS::detachHandler ( ) [private, virtual]

Reimplemented from PhidgetIK.

Definition at line 448 of file phidgetik_ros.cpp.

auto PhidgetIKROS::inputChangeHandler ( int  index,
int  inputState 
) [private, virtual]

Reimplemented from PhidgetIK.

Definition at line 274 of file phidgetik_ros.cpp.

auto PhidgetIKROS::onDigitalOutCallback ( const cob_phidgets::DigitalSensorConstPtr &  msg) [private]

Definition at line 376 of file phidgetik_ros.cpp.

auto PhidgetIKROS::outputChangeHandler ( int  index,
int  outputState 
) [private, virtual]

Reimplemented from PhidgetIK.

Definition at line 296 of file phidgetik_ros.cpp.

auto PhidgetIKROS::readParams ( XmlRpc::XmlRpcValue sensor_params) [private]

Definition at line 94 of file phidgetik_ros.cpp.

auto PhidgetIKROS::sensorChangeHandler ( int  index,
int  sensorValue 
) [private, virtual]

Reimplemented from PhidgetIK.

Definition at line 305 of file phidgetik_ros.cpp.

auto PhidgetIKROS::setDataRateCallback ( cob_phidgets::SetDataRate::Request &  req,
cob_phidgets::SetDataRate::Response &  res 
) [private]

Definition at line 399 of file phidgetik_ros.cpp.

auto PhidgetIKROS::setDigitalOutCallback ( cob_phidgets::SetDigitalSensor::Request &  req,
cob_phidgets::SetDigitalSensor::Response &  res 
) [private]

Definition at line 328 of file phidgetik_ros.cpp.

auto PhidgetIKROS::setTriggerValueCallback ( cob_phidgets::SetTriggerValue::Request &  req,
cob_phidgets::SetTriggerValue::Response &  res 
) [private]

Definition at line 405 of file phidgetik_ros.cpp.

auto PhidgetIKROS::update ( ) [private, virtual]

Reimplemented from PhidgetIK.

Definition at line 210 of file phidgetik_ros.cpp.


Member Data Documentation

std::string PhidgetIKROS::_board_name [private]

Definition at line 91 of file phidgetik_ros.h.

std::map<int, std::string> PhidgetIKROS::_indexNameMapAnalog [private]

Definition at line 103 of file phidgetik_ros.h.

std::map<std::string, int> PhidgetIKROS::_indexNameMapAnalogRev [private]

Definition at line 104 of file phidgetik_ros.h.

std::map<int, std::string> PhidgetIKROS::_indexNameMapDigitalIn [private]

Definition at line 105 of file phidgetik_ros.h.

std::map<std::string, int> PhidgetIKROS::_indexNameMapDigitalInRev [private]

Definition at line 106 of file phidgetik_ros.h.

std::map<int, std::string> PhidgetIKROS::_indexNameMapDigitalOut [private]

Definition at line 107 of file phidgetik_ros.h.

std::map<std::string, int> PhidgetIKROS::_indexNameMapDigitalOutRev [private]

Definition at line 108 of file phidgetik_ros.h.

std::map<int, std::string>::iterator PhidgetIKROS::_indexNameMapItr [private]

Definition at line 109 of file phidgetik_ros.h.

std::map<std::string, int>::iterator PhidgetIKROS::_indexNameMapRevItr [private]

Definition at line 110 of file phidgetik_ros.h.

std::mutex PhidgetIKROS::_mutex [private]

Definition at line 101 of file phidgetik_ros.h.

Definition at line 82 of file phidgetik_ros.h.

Definition at line 100 of file phidgetik_ros.h.

Definition at line 83 of file phidgetik_ros.h.

Definition at line 84 of file phidgetik_ros.h.

Definition at line 90 of file phidgetik_ros.h.

Definition at line 87 of file phidgetik_ros.h.

Definition at line 86 of file phidgetik_ros.h.

Definition at line 88 of file phidgetik_ros.h.

Definition at line 85 of file phidgetik_ros.h.


The documentation for this class was generated from the following files:


cob_phidgets
Author(s): Florian Weisshardt
autogenerated on Thu Aug 27 2015 12:46:06