Public Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
phidgets::IKRosI Class Reference

#include <ik_ros_i.h>

Inheritance diagram for phidgets::IKRosI:
Inheritance graph
[legend]

Public Member Functions

 IKRosI (ros::NodeHandle nh, ros::NodeHandle nh_private)
 
- Public Member Functions inherited from phidgets::IK
 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 open (int serial_number)
 
 Phidget ()
 
int waitForAttachment (int timeout)
 
 ~Phidget ()
 

Protected Attributes

std::vector< ros::Publisherin_pubs_
 
int n_in
 
int n_out
 
int n_sensors
 
ros::ServiceServer out_srv_
 
std::vector< boost::shared_ptr< OutputSetter > > out_subs_
 
std::vector< ros::Publishersensor_pubs_
 
- Protected Attributes inherited from phidgets::IK
CPhidgetInterfaceKitHandle ik_handle_
 
- Protected Attributes inherited from phidgets::Phidget
CPhidgetHandle handle_
 

Private Member Functions

void initDevice ()
 
void inputHandler (int index, int inputValue)
 
void sensorHandler (int index, int sensorValue)
 
bool set_srv_callback (phidgets_ik::SetDigitalOutput::Request &req, phidgets_ik::SetDigitalOutput::Response &res)
 

Private Attributes

ros::NodeHandle nh_
 
ros::NodeHandle nh_private_
 
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)
 
virtual void registerHandlers ()
 

Detailed Description

Definition at line 25 of file ik_ros_i.h.

Constructor & Destructor Documentation

phidgets::IKRosI::IKRosI ( ros::NodeHandle  nh,
ros::NodeHandle  nh_private 
)

Definition at line 5 of file ik_ros_i.cpp.

Member Function Documentation

void phidgets::IKRosI::initDevice ( )
private

Definition at line 19 of file ik_ros_i.cpp.

void phidgets::IKRosI::inputHandler ( int  index,
int  inputValue 
)
privatevirtual

Reimplemented from phidgets::IK.

Definition at line 76 of file ik_ros_i.cpp.

void phidgets::IKRosI::sensorHandler ( int  index,
int  sensorValue 
)
privatevirtual

Reimplemented from phidgets::IK.

Definition at line 62 of file ik_ros_i.cpp.

bool phidgets::IKRosI::set_srv_callback ( phidgets_ik::SetDigitalOutput::Request &  req,
phidgets_ik::SetDigitalOutput::Response &  res 
)
private

Definition at line 85 of file ik_ros_i.cpp.

Member Data Documentation

std::vector<ros::Publisher> phidgets::IKRosI::in_pubs_
protected

Definition at line 37 of file ik_ros_i.h.

int phidgets::IKRosI::n_in
protected

Definition at line 34 of file ik_ros_i.h.

int phidgets::IKRosI::n_out
protected

Definition at line 35 of file ik_ros_i.h.

int phidgets::IKRosI::n_sensors
protected

Definition at line 36 of file ik_ros_i.h.

ros::NodeHandle phidgets::IKRosI::nh_
private

Definition at line 44 of file ik_ros_i.h.

ros::NodeHandle phidgets::IKRosI::nh_private_
private

Definition at line 45 of file ik_ros_i.h.

ros::ServiceServer phidgets::IKRosI::out_srv_
protected

Definition at line 39 of file ik_ros_i.h.

std::vector<boost::shared_ptr<OutputSetter> > phidgets::IKRosI::out_subs_
protected

Definition at line 40 of file ik_ros_i.h.

std::vector<ros::Publisher> phidgets::IKRosI::sensor_pubs_
protected

Definition at line 38 of file ik_ros_i.h.

const float phidgets::IKRosI::VREF
private

Definition at line 47 of file ik_ros_i.h.


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


phidgets_ik
Author(s): James Sarrett
autogenerated on Tue May 7 2019 03:19:28