38 #include <phidget21.h>
42 #include <ros/package.h>
44 #include <boost/asio.hpp>
45 #include <boost/bind.hpp>
46 #include <boost/thread.hpp>
48 #include <sensor_msgs/Range.h>
49 #include <pressure_cells/SenVal.h>
50 #include <visualization_msgs/Marker.h>
57 PhidgetClass(boost::asio::io_service& io_service,ros::NodeHandle& nh_);
62 int ErrorHandler(CPhidgetHandle IFK,
int ErrorCode,
const char *unknown);
64 void irHandler(boost::system::error_code
const& cError);
125 boost::asio::deadline_timer
ir_timer;
142 CPhidgetInterfaceKitHandle
ifKit;
int readFSRSensors()
FSR FUNCTIONS.
ros::Publisher LC_marker_pub
int readLCSensors()
LC FUNCTIONS.
ros::Publisher ir1_publisher
boost::asio::deadline_timer ir_timer
ros::Publisher FSR_marker_pub
visualization_msgs::Marker FSR_marker
int ErrorHandler(CPhidgetHandle IFK, int ErrorCode, const char *unknown)
visualization_msgs::Marker LC_marker
pressure_cells::SenVal ForceVal
void highRateHandler(boost::system::error_code const &cError)
LC/FSR Handler - High rate 100Hz.
void LC_pub()
Markers declaration.
ros::Publisher ForceVal_publisher
void irHandler(boost::system::error_code const &cError)
IR Handler - Low rate 40Hz.
int readIRSensors()
IR Sensor FUNCTIONS.
boost::asio::deadline_timer high_rate_timer
ros::Publisher ir2_publisher
CPhidgetInterfaceKitHandle ifKit
PhidgetClass(boost::asio::io_service &io_service)
int calibrateFSRSensors()
int AttachHandler(CPhidgetHandle IFK)
int DetachHandler(CPhidgetHandle IFK)