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


cob_phidgets
Author(s): Florian Weisshardt
autogenerated on Sat Jun 8 2019 21:02:14