phidgets_range_sensors.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 // see http://www.phidgets.com/products.php?category=2&product_id=3520_0
19 // distance calculation: Distance (cm) = 2076/(SensorValue - 11) (the formula is only valid for a SensorValue between 80 to 530)
20 // 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)
21 
22 #include "ros/ros.h"
23 #include "std_msgs/Bool.h"
24 #include "sensor_msgs/Range.h"
25 
26 #include <libphidgets/phidget21.h>
27 #include <sstream>
28 
29 class Sensor
30 {
34  std::list<int> vals_;
35  std::string frame_id_;
36 public:
37 
38  Sensor(const std::string &fr_id, const int id, const int filter_size = 10) :
39  id_(id), filter_size_(filter_size), frame_id_(fr_id)
40  {
41  pub_range_ = n_.advertise<sensor_msgs::Range>(frame_id_, 0);
42  }
43 
44  void publish()
45  {
46  pub_range_.publish((sensor_msgs::Range) *this);
47  }
48 
49  operator sensor_msgs::Range() const
50  {
51  sensor_msgs::Range msg;
52  msg.header.stamp = ros::Time::now();
53  msg.header.frame_id = frame_id_;
54  msg.radiation_type = sensor_msgs::Range::INFRARED;
55  msg.min_range = 0.04;
56  msg.max_range = 0.3;
57  msg.field_of_view = 0; //not given!
58 
59  int sum = 0, num = 0;
60  for (std::list<int>::const_iterator it = vals_.begin();
61  it != vals_.end(); it++)
62  {
63  sum += *it;
64  ++num;
65  }
66  msg.range = 20.76 / (sum / (double) num - 11.);
67 
68  return msg;
69  }
70 
71  int getId() const
72  {
73  return id_;
74  }
75 
76  void update(const int v)
77  {
78  if ((int)vals_.size() < filter_size_)
79  vals_.push_back(v);
80  else
81  {
82  vals_.push_back(v);
83  vals_.pop_front();
84  }
85  }
86 
87 };
88 
89 void display_generic_properties(CPhidgetHandle phid)
90 {
91  int sernum, version;
92  const char *deviceptr, *label;
93  CPhidget_getDeviceType(phid, &deviceptr);
94  CPhidget_getSerialNumber(phid, &sernum);
95  CPhidget_getDeviceVersion(phid, &version);
96  CPhidget_getDeviceLabel(phid, &label);
97 
98  ROS_INFO("%s", deviceptr);
99  ROS_INFO("Version: %8d SerialNumber: %10d", version, sernum);
100  ROS_INFO("Label: %s", label);
101  return;
102 }
103 
104 int IFK_AttachHandler(CPhidgetHandle IFK, void *userptr)
105 {
106  //CPhidgetInterfaceKit_setSensorChangeTrigger((CPhidgetInterfaceKitHandle)IFK, 0, 0);
107  //printf("Attach handler ran!\n");
108  return 0;
109 }
110 
111 int IFK_SensorChangeHandler(CPhidgetInterfaceKitHandle IFK, void *userptr,
112  int Index, int Value)
113 {
114  std::vector<Sensor>* g_sensors = (std::vector<Sensor>*) userptr;
115  for (size_t i = 0; i < g_sensors->size(); i++)
116  if ((*g_sensors)[i].getId() == Index)
117  (*g_sensors)[i].update(Value);
118  return 0;
119 }
120 
121 int main(int argc, char **argv)
122 {
123  ros::init(argc, argv, "cob_phidgets");
124 
125  ros::NodeHandle nh_("~");
126  std::vector<Sensor> g_sensors;
127  if (nh_.hasParam("sensors"))
128  {
130  nh_.param("sensors", v, v);
131  for (int i = 0; i < v.size(); i++)
132  {
133  ROS_ASSERT(v[i].size()>=2);
134 
135  int id = v[i][0];
136  std::string fr_id = v[i][1];
137  int filter = v.size() > 2 ? (int) v[i][2] : 10;
138 
139  g_sensors.push_back(Sensor(fr_id, id, filter));
140  }
141  }
142  else
143  {
144  ROS_ERROR("Parameter sensors not set, shutting down node...");
145  nh_.shutdown();
146  return false;
147  }
148 
149  ros::Rate loop_rate(10);
150 
151  //init and open phidget
152  int numInputs, numOutputs, numSensors;
153  int err;
154 
155  CPhidgetInterfaceKitHandle IFK = 0;
156  CPhidget_enableLogging(PHIDGET_LOG_VERBOSE, NULL);
157  CPhidgetInterfaceKit_create(&IFK);
158  CPhidgetInterfaceKit_set_OnSensorChange_Handler(IFK,
159  IFK_SensorChangeHandler, (void*) &g_sensors);
160  CPhidget_set_OnAttach_Handler((CPhidgetHandle) IFK, IFK_AttachHandler,
161  NULL);
162  //opening phidget
163  CPhidget_open((CPhidgetHandle) IFK, -1);
164 
165  //wait 5 seconds for attachment
166  ROS_INFO("waiting for phidgets attachement...");
167  if ((err = CPhidget_waitForAttachment((CPhidgetHandle) IFK, 10000))
168  != EPHIDGET_OK)
169  {
170  const char *errStr;
171  CPhidget_getErrorDescription(err, &errStr);
172  ROS_ERROR("Error waiting for attachment: (%d): %s", err, errStr);
173  goto exit;
174  }
175  ROS_INFO("... attached");
176 
177  display_generic_properties((CPhidgetHandle) IFK);
178  CPhidgetInterfaceKit_getOutputCount((CPhidgetInterfaceKitHandle) IFK,
179  &numOutputs);
180  CPhidgetInterfaceKit_getInputCount((CPhidgetInterfaceKitHandle) IFK,
181  &numInputs);
182  CPhidgetInterfaceKit_getSensorCount((CPhidgetInterfaceKitHandle) IFK,
183  &numSensors);
184  //CPhidgetInterfaceKit_setOutputState((CPhidgetInterfaceKitHandle)IFK, 0, 1);
185 
186  ROS_INFO(
187  "Sensors:%d Inputs:%d Outputs:%d", numSensors, numInputs, numOutputs);
188 
189  while (ros::ok())
190  {
191  for (size_t i = 0; i < g_sensors.size(); i++)
192  g_sensors[i].publish();
193  ros::spinOnce();
194  loop_rate.sleep();
195  }
196 
197  exit: CPhidget_close((CPhidgetHandle) IFK);
198  CPhidget_delete((CPhidgetHandle) IFK);
199 
200  return 0;
201 }
int main(int argc, char **argv)
int IFK_AttachHandler(CPhidgetHandle IFK, void *userptr)
void publish(const boost::shared_ptr< M > &message) const
int size() const
std::string frame_id_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int getId() const
void update(const int v)
Sensor(const std::string &fr_id, const int id, const int filter_size=10)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
int i
Definition: tablet_leer.c:27
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int IFK_SensorChangeHandler(CPhidgetInterfaceKitHandle IFK, void *userptr, int Index, int Value)
void display_generic_properties(CPhidgetHandle phid)
bool sleep()
ros::NodeHandle n_
std::list< int > vals_
static Time now()
bool hasParam(const std::string &key) const
#define ROS_ASSERT(cond)
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
ros::Publisher pub_range_


cob_phidgets
Author(s): Florian Weisshardt
autogenerated on Wed Apr 7 2021 02:11:43