#include <ik_ros_i.h>

Public Member Functions | |
| IKRosI (ros::NodeHandle nh, ros::NodeHandle nh_private) | |
Public Member Functions inherited from phidgets::IK | |
| int | getInputCount () const |
| int | getOutputCount () const |
| int | getSensorCount () const |
| int | getSensorRawValue (int index) const |
| IK () | |
| bool | setOutputState (int index, bool state) const |
| virtual | ~IK () |
Public Member Functions inherited from phidgets::Phidget | |
| int | close () |
| std::string | getDeviceLabel () |
| std::string | getDeviceName () |
| int | getDeviceSerialNumber () |
| std::string | getDeviceType () |
| int | getDeviceVersion () |
| std::string | getLibraryVersion () |
| int | openAndWaitForAttachment (int serial_number, int timeout) |
| Phidget () | |
| virtual | ~Phidget () |
Private Member Functions | |
| void | initDevice () |
| void | inputHandler (int index, int inputValue) override |
| void | sensorHandler (int index, int sensorValue) override |
| bool | set_srv_callback (phidgets_msgs::SetDigitalOutput::Request &req, phidgets_msgs::SetDigitalOutput::Response &res) |
Private Attributes | |
| std::vector< ros::Publisher > | in_pubs_ |
| int | n_in |
| int | n_out |
| int | n_sensors |
| ros::NodeHandle | nh_ |
| ros::NodeHandle | nh_private_ |
| ros::ServiceServer | out_srv_ |
| std::vector< std::shared_ptr< OutputSetter > > | out_subs_ |
| std::vector< ros::Publisher > | sensor_pubs_ |
| const float | VREF |
Additional Inherited Members | |
Static Public Member Functions inherited from phidgets::Phidget | |
| static std::string | getErrorDescription (int errorCode) |
Protected Member Functions inherited from phidgets::Phidget | |
| virtual void | attachHandler () |
| virtual void | detachHandler () |
| virtual void | errorHandler (int error) |
| void | init (CPhidgetHandle handle) |
| void | registerHandlers () |
Definition at line 27 of file ik_ros_i.h.
|
explicit |
Definition at line 5 of file ik_ros_i.cpp.
|
private |
Definition at line 19 of file ik_ros_i.cpp.
|
overrideprivatevirtual |
Reimplemented from phidgets::IK.
Definition at line 82 of file ik_ros_i.cpp.
|
overrideprivatevirtual |
Reimplemented from phidgets::IK.
Definition at line 67 of file ik_ros_i.cpp.
|
private |
Definition at line 92 of file ik_ros_i.cpp.
|
private |
Definition at line 36 of file ik_ros_i.h.
|
private |
Definition at line 33 of file ik_ros_i.h.
|
private |
Definition at line 34 of file ik_ros_i.h.
|
private |
Definition at line 35 of file ik_ros_i.h.
|
private |
Definition at line 41 of file ik_ros_i.h.
|
private |
Definition at line 42 of file ik_ros_i.h.
|
private |
Definition at line 38 of file ik_ros_i.h.
|
private |
Definition at line 39 of file ik_ros_i.h.
|
private |
Definition at line 37 of file ik_ros_i.h.
|
private |
Definition at line 44 of file ik_ros_i.h.