$search
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 00006 #include "ros/ros.h" 00007 #include "std_msgs/Bool.h" 00008 #include "sensor_msgs/Range.h" 00009 00010 #include <libphidgets/phidget21.h> 00011 #include <sstream> 00012 00013 class Sensor 00014 { 00015 ros::NodeHandle n_; 00016 ros::Publisher pub_range_; 00017 int id_, filter_size_; 00018 std::list<int> vals_; 00019 std::string frame_id_; 00020 public: 00021 00022 Sensor(const std::string &fr_id, const int id, const int filter_size=10):id_(id),filter_size_(filter_size),frame_id_(fr_id) { 00023 char buffer[256]; 00024 sprintf(buffer,"range_%d",id); 00025 pub_range_ = n_.advertise<sensor_msgs::Range>(buffer, 0); 00026 } 00027 00028 void publish() 00029 { 00030 pub_range_.publish((sensor_msgs::Range)*this); 00031 } 00032 00033 operator sensor_msgs::Range() const 00034 { 00035 sensor_msgs::Range msg; 00036 msg.header.stamp = ros::Time::now(); 00037 msg.header.frame_id = frame_id_; 00038 msg.radiation_type = sensor_msgs::Range::INFRARED; 00039 msg.min_range = 0.04; 00040 msg.max_range = 0.3; 00041 msg.field_of_view = 0; //not given! 00042 00043 int sum=0, num=0; 00044 for(std::list<int>::const_iterator it=vals_.begin(); 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 {return id_;} 00055 00056 void update(const int v) 00057 { 00058 if(vals_.size()<filter_size_) vals_.push_back(v); 00059 else {vals_.push_back(v); vals_.pop_front();} 00060 } 00061 00062 }; 00063 00064 int i; 00065 00066 bool bOccupied_; 00067 std::vector<Sensor> g_sensors; 00068 00069 void display_generic_properties(CPhidgetHandle phid) 00070 { 00071 int sernum, version; 00072 const char *deviceptr, *label; 00073 CPhidget_getDeviceType(phid, &deviceptr); 00074 CPhidget_getSerialNumber(phid, &sernum); 00075 CPhidget_getDeviceVersion(phid, &version); 00076 CPhidget_getDeviceLabel(phid, &label); 00077 00078 ROS_INFO("%s", deviceptr); 00079 ROS_INFO("Version: %8d SerialNumber: %10d", version, sernum); 00080 ROS_INFO("Label: %s", label); 00081 return; 00082 } 00083 00084 int IFK_AttachHandler(CPhidgetHandle IFK, void *userptr) 00085 { 00086 //CPhidgetInterfaceKit_setSensorChangeTrigger((CPhidgetInterfaceKitHandle)IFK, 0, 0); 00087 //printf("Attach handler ran!\n"); 00088 return 0; 00089 } 00090 00091 00092 int IFK_SensorChangeHandler(CPhidgetInterfaceKitHandle IFK, void *userptr, int Index, int Value) 00093 { 00094 00095 for(size_t i=0; i<g_sensors.size(); i++) 00096 if(g_sensors[i].getId()==Index) g_sensors[i].update(Value); 00097 return 0; 00098 } 00099 00100 int main(int argc, char **argv) 00101 { 00102 ros::init(argc, argv, "cob_phidgets"); 00103 00104 ros::NodeHandle nh_("~"); 00105 00106 if (nh_.hasParam("sensors")) 00107 { 00108 XmlRpc::XmlRpcValue v; 00109 nh_.param("sensors", v, v); 00110 for(int i =0; i < v.size(); i++) 00111 { 00112 ROS_ASSERT(v[i].size()>=2); 00113 00114 int id = v[i][0]; 00115 std::string fr_id = v[i][1]; 00116 int filter = v.size()>2?(int)v[i][2]:10; 00117 00118 g_sensors.push_back(Sensor(fr_id,id,filter)); 00119 } 00120 } 00121 else 00122 { 00123 ROS_ERROR("Parameter sensors not set, shutting down node..."); 00124 nh_.shutdown(); 00125 return false; 00126 } 00127 00128 00129 ros::Rate loop_rate(10); 00130 00131 //init and open phidget 00132 int numInputs, numOutputs, numSensors; 00133 int err; 00134 00135 CPhidgetInterfaceKitHandle IFK = 0; 00136 CPhidget_enableLogging(PHIDGET_LOG_VERBOSE, NULL); 00137 CPhidgetInterfaceKit_create(&IFK); 00138 CPhidgetInterfaceKit_set_OnSensorChange_Handler(IFK, IFK_SensorChangeHandler, NULL); 00139 CPhidget_set_OnAttach_Handler((CPhidgetHandle)IFK, IFK_AttachHandler, NULL); 00140 //opening phidget 00141 CPhidget_open((CPhidgetHandle)IFK, -1); 00142 00143 //wait 5 seconds for attachment 00144 ROS_INFO("waiting for phidgets attachement..."); 00145 if((err = CPhidget_waitForAttachment((CPhidgetHandle)IFK, 10000)) != EPHIDGET_OK ) 00146 { 00147 const char *errStr; 00148 CPhidget_getErrorDescription(err, &errStr); 00149 ROS_ERROR("Error waiting for attachment: (%d): %s",err,errStr); 00150 goto exit; 00151 } 00152 ROS_INFO("... attached"); 00153 00154 display_generic_properties((CPhidgetHandle)IFK); 00155 CPhidgetInterfaceKit_getOutputCount((CPhidgetInterfaceKitHandle)IFK, &numOutputs); 00156 CPhidgetInterfaceKit_getInputCount((CPhidgetInterfaceKitHandle)IFK, &numInputs); 00157 CPhidgetInterfaceKit_getSensorCount((CPhidgetInterfaceKitHandle)IFK, &numSensors); 00158 //CPhidgetInterfaceKit_setOutputState((CPhidgetInterfaceKitHandle)IFK, 0, 1); 00159 00160 ROS_INFO("Sensors:%d Inputs:%d Outputs:%d", numSensors, numInputs, numOutputs); 00161 00162 while (ros::ok()) 00163 { 00164 for(size_t i=0; i<g_sensors.size(); i++) g_sensors[i].publish(); 00165 ros::spinOnce(); 00166 loop_rate.sleep(); 00167 } 00168 00169 exit: 00170 CPhidget_close((CPhidgetHandle)IFK); 00171 CPhidget_delete((CPhidgetHandle)IFK); 00172 00173 00174 return 0; 00175 }