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

#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
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::Publisherin_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::Publishersensor_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 ()
 

Detailed Description

Definition at line 27 of file ik_ros_i.h.

Constructor & Destructor Documentation

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

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 
)
overrideprivatevirtual

Reimplemented from phidgets::IK.

Definition at line 82 of file ik_ros_i.cpp.

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

Reimplemented from phidgets::IK.

Definition at line 67 of file ik_ros_i.cpp.

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

Definition at line 92 of file ik_ros_i.cpp.

Member Data Documentation

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

Definition at line 36 of file ik_ros_i.h.

int phidgets::IKRosI::n_in
private

Definition at line 33 of file ik_ros_i.h.

int phidgets::IKRosI::n_out
private

Definition at line 34 of file ik_ros_i.h.

int phidgets::IKRosI::n_sensors
private

Definition at line 35 of file ik_ros_i.h.

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

Definition at line 41 of file ik_ros_i.h.

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

Definition at line 42 of file ik_ros_i.h.

ros::ServiceServer phidgets::IKRosI::out_srv_
private

Definition at line 38 of file ik_ros_i.h.

std::vector<std::shared_ptr<OutputSetter> > phidgets::IKRosI::out_subs_
private

Definition at line 39 of file ik_ros_i.h.

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

Definition at line 37 of file ik_ros_i.h.

const float phidgets::IKRosI::VREF
private

Definition at line 44 of file ik_ros_i.h.


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


phidgets_ik
Author(s): James Sarrett, Russel Howe
autogenerated on Fri Apr 9 2021 02:56:07