phidgets_range_sensors.cpp
Go to the documentation of this file.
00001 // see http://www.phidgets.com/products.php?category=2&product_id=3520_0
00002 // distance calculation: Distance (cm) = 2076/(SensorValue - 11)             (the formula is only valid for a SensorValue between 80 to 530)
00003 // TODO: separate into two packages: cob_phidgets_driver (publishing only raw values as sensor_msgs/Range message) and cob_tray_status (evaluating the Range messages to decide if tray is occupied or not, eventually also at which position it is occupied) 
00004 
00005 #include "ros/ros.h"
00006 #include "std_msgs/Bool.h"
00007 #include "sensor_msgs/Range.h"
00008 
00009 #include <libphidgets/phidget21.h>
00010 #include <sstream>
00011 
00012 class Sensor
00013 {
00014         ros::NodeHandle n_;
00015         ros::Publisher pub_range_;
00016         int id_, filter_size_;
00017         std::list<int> vals_;
00018         std::string frame_id_;
00019 public:
00020 
00021         Sensor(const std::string &fr_id, const int id, const int filter_size = 10) :
00022                         id_(id), filter_size_(filter_size), frame_id_(fr_id)
00023         {
00024                 pub_range_ = n_.advertise<sensor_msgs::Range>(frame_id_, 0);
00025         }
00026 
00027         void publish()
00028         {
00029                 pub_range_.publish((sensor_msgs::Range) *this);
00030         }
00031 
00032         operator sensor_msgs::Range() const
00033         {
00034                 sensor_msgs::Range msg;
00035                 msg.header.stamp = ros::Time::now();
00036                 msg.header.frame_id = frame_id_;
00037                 msg.radiation_type = sensor_msgs::Range::INFRARED;
00038                 msg.min_range = 0.04;
00039                 msg.max_range = 0.3;
00040                 msg.field_of_view = 0; //not given!
00041 
00042                 int sum = 0, num = 0;
00043                 for (std::list<int>::const_iterator it = vals_.begin();
00044                                 it != vals_.end(); it++)
00045                 {
00046                         sum += *it;
00047                         ++num;
00048                 }
00049                 msg.range = 20.76 / (sum / (double) num - 11.);
00050 
00051                 return msg;
00052         }
00053 
00054         int getId() const
00055         {
00056                 return id_;
00057         }
00058 
00059         void update(const int v)
00060         {
00061                 if ((int)vals_.size() < filter_size_)
00062                         vals_.push_back(v);
00063                 else
00064                 {
00065                         vals_.push_back(v);
00066                         vals_.pop_front();
00067                 }
00068         }
00069 
00070 };
00071 
00072 void display_generic_properties(CPhidgetHandle phid)
00073 {
00074         int sernum, version;
00075         const char *deviceptr, *label;
00076         CPhidget_getDeviceType(phid, &deviceptr);
00077         CPhidget_getSerialNumber(phid, &sernum);
00078         CPhidget_getDeviceVersion(phid, &version);
00079         CPhidget_getDeviceLabel(phid, &label);
00080 
00081         ROS_INFO("%s", deviceptr);
00082         ROS_INFO("Version: %8d SerialNumber: %10d", version, sernum);
00083         ROS_INFO("Label: %s", label);
00084         return;
00085 }
00086 
00087 int IFK_AttachHandler(CPhidgetHandle IFK, void *userptr)
00088 {
00089         //CPhidgetInterfaceKit_setSensorChangeTrigger((CPhidgetInterfaceKitHandle)IFK, 0, 0);
00090         //printf("Attach handler ran!\n");
00091         return 0;
00092 }
00093 
00094 int IFK_SensorChangeHandler(CPhidgetInterfaceKitHandle IFK, void *userptr,
00095                 int Index, int Value)
00096 {
00097         std::vector<Sensor>* g_sensors = (std::vector<Sensor>*) userptr;
00098         for (size_t i = 0; i < g_sensors->size(); i++)
00099                 if ((*g_sensors)[i].getId() == Index)
00100                         (*g_sensors)[i].update(Value);
00101         return 0;
00102 }
00103 
00104 int main(int argc, char **argv)
00105 {
00106         ros::init(argc, argv, "cob_phidgets");
00107 
00108         ros::NodeHandle nh_("~");
00109         std::vector<Sensor> g_sensors;
00110         if (nh_.hasParam("sensors"))
00111         {
00112                 XmlRpc::XmlRpcValue v;
00113                 nh_.param("sensors", v, v);
00114                 for (int i = 0; i < v.size(); i++)
00115                 {
00116                         ROS_ASSERT(v[i].size()>=2);
00117 
00118                         int id = v[i][0];
00119                         std::string fr_id = v[i][1];
00120                         int filter = v.size() > 2 ? (int) v[i][2] : 10;
00121 
00122                         g_sensors.push_back(Sensor(fr_id, id, filter));
00123                 }
00124         }
00125         else
00126         {
00127                 ROS_ERROR("Parameter sensors not set, shutting down node...");
00128                 nh_.shutdown();
00129                 return false;
00130         }
00131 
00132         ros::Rate loop_rate(10);
00133 
00134         //init and open phidget
00135         int numInputs, numOutputs, numSensors;
00136         int err;
00137 
00138         CPhidgetInterfaceKitHandle IFK = 0;
00139         CPhidget_enableLogging(PHIDGET_LOG_VERBOSE, NULL);
00140         CPhidgetInterfaceKit_create(&IFK);
00141         CPhidgetInterfaceKit_set_OnSensorChange_Handler(IFK,
00142                         IFK_SensorChangeHandler, (void*) &g_sensors);
00143         CPhidget_set_OnAttach_Handler((CPhidgetHandle) IFK, IFK_AttachHandler,
00144                         NULL);
00145         //opening phidget
00146         CPhidget_open((CPhidgetHandle) IFK, -1);
00147 
00148         //wait 5 seconds for attachment
00149         ROS_INFO("waiting for phidgets attachement...");
00150         if ((err = CPhidget_waitForAttachment((CPhidgetHandle) IFK, 10000))
00151                         != EPHIDGET_OK)
00152         {
00153                 const char *errStr;
00154                 CPhidget_getErrorDescription(err, &errStr);
00155                 ROS_ERROR("Error waiting for attachment: (%d): %s", err, errStr);
00156                 goto exit;
00157         }
00158         ROS_INFO("... attached");
00159 
00160         display_generic_properties((CPhidgetHandle) IFK);
00161         CPhidgetInterfaceKit_getOutputCount((CPhidgetInterfaceKitHandle) IFK,
00162                         &numOutputs);
00163         CPhidgetInterfaceKit_getInputCount((CPhidgetInterfaceKitHandle) IFK,
00164                         &numInputs);
00165         CPhidgetInterfaceKit_getSensorCount((CPhidgetInterfaceKitHandle) IFK,
00166                         &numSensors);
00167         //CPhidgetInterfaceKit_setOutputState((CPhidgetInterfaceKitHandle)IFK, 0, 1);
00168 
00169         ROS_INFO(
00170                         "Sensors:%d Inputs:%d Outputs:%d", numSensors, numInputs, numOutputs);
00171 
00172         while (ros::ok())
00173         {
00174                 for (size_t i = 0; i < g_sensors.size(); i++)
00175                         g_sensors[i].publish();
00176                 ros::spinOnce();
00177                 loop_rate.sleep();
00178         }
00179 
00180         exit: CPhidget_close((CPhidgetHandle) IFK);
00181         CPhidget_delete((CPhidgetHandle) IFK);
00182 
00183         return 0;
00184 }


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