phidgetik_ros.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 
19 
20 PhidgetIKROS::PhidgetIKROS(ros::NodeHandle nh, int serial_num, std::string board_name, XmlRpc::XmlRpcValue* sensor_params, SensingMode mode)
21  :PhidgetIK(mode), _nh(nh), _serial_num(serial_num), _board_name(board_name)
22 {
23  ros::NodeHandle tmpHandle("~");
24  ros::NodeHandle nodeHandle(tmpHandle, board_name);
25  _outputChanged.updated=false;
28 
29  _pubAnalog = _nh.advertise<cob_phidgets::AnalogSensor>("analog_sensors", 1);
30  _pubDigital = _nh.advertise<cob_phidgets::DigitalSensor>("digital_sensors", 1);
31  _subDigital = _nh.subscribe("set_digital_sensor", 1, &PhidgetIKROS::onDigitalOutCallback, this);
32 
33  _srvDigitalOut = nodeHandle.advertiseService("set_digital", &PhidgetIKROS::setDigitalOutCallback, this);
34  _srvDataRate = nodeHandle.advertiseService("set_data_rate", &PhidgetIKROS::setDataRateCallback, this);
35  _srvTriggerValue = nodeHandle.advertiseService("set_trigger_value", &PhidgetIKROS::setTriggerValueCallback, this);
36 
37  if(init(_serial_num) != EPHIDGET_OK)
38  {
39  ROS_ERROR("Error open Phidget Board on serial %d. Message: %s",_serial_num, this->getErrorDescription(this->getError()).c_str());
40  }
41  if(waitForAttachment(10000) != EPHIDGET_OK)
42  {
43  ROS_ERROR("Error waiting for Attachment. Message: %s",this->getErrorDescription(this->getError()).c_str());
44  }
45  readParams(sensor_params);
46 }
47 
49 {
50 }
51 
52 auto PhidgetIKROS::readParams(XmlRpc::XmlRpcValue* sensor_params) -> void
53 {
54  if(sensor_params != nullptr)
55  {
56  for(auto& sensor : *sensor_params)
57  {
58  std::string name = sensor.first;
59  XmlRpc::XmlRpcValue value = sensor.second;
60  if(!value.hasMember("type"))
61  {
62  ROS_ERROR("Sensor Param '%s' has no 'type' member. Ignoring param!", name.c_str());
63  continue;
64  }
65  if(!value.hasMember("index"))
66  {
67  ROS_ERROR("Sensor Param '%s' has no 'index' member. Ignoring param!", name.c_str());
68  continue;
69  }
70  XmlRpc::XmlRpcValue value_type = value["type"];
71  XmlRpc::XmlRpcValue value_index = value["index"];
72  std::string type = value_type;
73  int index = value_index;
74 
75  if(type == "analog")
76  _indexNameMapAnalog.insert(std::make_pair(index, name));
77  else if(type == "digital_in")
78  _indexNameMapDigitalIn.insert(std::make_pair(index, name));
79  else if(type == "digital_out")
80  _indexNameMapDigitalOut.insert(std::make_pair(index, name));
81  else
82  ROS_ERROR("Type '%s' in sensor param '%s' is unkown", type.c_str(), name.c_str());
83 
84  if(value.hasMember("change_trigger"))
85  {
86  XmlRpc::XmlRpcValue value_change_trigger = value["change_trigger"];
87  int change_trigger = value_change_trigger;
88  ROS_WARN("Setting change trigger to %d for sensor %s with index %d ",change_trigger, name.c_str(), index);
89  setSensorChangeTrigger(index, change_trigger);
90  }
91  if(value.hasMember("data_rate"))
92  {
93  XmlRpc::XmlRpcValue value_data_rate = value["data_rate"];
94  int data_rate = value_data_rate;
95  ROS_WARN("Setting data rate to %d for sensor %s with index %d ",data_rate, name.c_str(), index);
96  setDataRate(index, data_rate);
97  }
98  }
99  }
100  //fill up rest of maps with default values
101  int count = this->getInputCount();
102  for(int i = 0; i < count; i++)
103  {
106  {
107  std::stringstream ss;
108  ss << _board_name << "/" << "in/" << i;
109  _indexNameMapDigitalIn.insert(std::make_pair(i, ss.str()));
110  }
111  }
112  count = this->getOutputCount();
113  for(int i = 0; i < count; i++)
114  {
117  {
118  std::stringstream ss;
119  ss << _board_name << "/" << "out/" << i;
120  _indexNameMapDigitalOut.insert(std::make_pair(i, ss.str()));
121  }
122  }
123  count = this->getSensorCount();
124  for(int i = 0; i < count; i++)
125  {
128  {
129  std::stringstream ss;
130  ss << _board_name << "/" << i;
131  _indexNameMapAnalog.insert(std::make_pair(i, ss.str()));
132  }
133  }
134 
135  //fill up reverse mapping
136  count = this->getInputCount();
137  for(int i = 0; i < count; i++)
138  {
141  {
142  std::stringstream ss;
143  ss << _board_name << "/" << "in/" << i;
144 
145  _indexNameMapDigitalInRev.insert(std::make_pair(_indexNameMapDigitalIn[i],i));
146  }
147  }
148  count = this->getOutputCount();
149  for(int i = 0; i < count; i++)
150  {
153  {
154  _indexNameMapDigitalOutRev.insert(std::make_pair(_indexNameMapDigitalOut[i],i));
155  }
156  }
157  count = this->getSensorCount();
158  for(int i = 0; i < count; i++)
159  {
162  {
163  _indexNameMapAnalogRev.insert(std::make_pair(_indexNameMapAnalog[i],i));
164  }
165  }
166 }
167 
168 auto PhidgetIKROS::update() -> void
169 {
170  int count = this->getInputCount();
171  cob_phidgets::DigitalSensor msg_digit;
172  std::vector<std::string> names;
173  std::vector<signed char> states;
174 
175  //------- publish digital input states ----------//
176  for(int i = 0; i < count; i++)
177  {
178  std::string name;
181  name = (*_indexNameMapItr).second;
182  names.push_back(name);
183  states.push_back(this->getInputState(i));
184  }
185  msg_digit.header.stamp = ros::Time::now();
186  msg_digit.uri = names;
187  msg_digit.state = states;
188 
189  _pubDigital.publish(msg_digit);
190 
191  //------- publish digital output states ----------//
192  names.clear();
193  states.clear();
194  count = this->getOutputCount();
195  for(int i = 0; i < count; i++)
196  {
197  std::string name;
200  name = (*_indexNameMapItr).second;
201  names.push_back(name);
202  states.push_back(this->getOutputState(i));
203  }
204  msg_digit.header.stamp = ros::Time::now();
205  msg_digit.uri = names;
206  msg_digit.state = states;
207 
208  _pubDigital.publish(msg_digit);
209 
210 
211  //------- publish analog input states ----------//
212  cob_phidgets::AnalogSensor msg_analog;
213  names.clear();
214  std::vector<short int> values;
215  count = this->getSensorCount();
216  for(int i = 0; i < count; i++)
217  {
218  std::string name;
221  name = (*_indexNameMapItr).second;
222  names.push_back(name);
223  values.push_back(this->getSensorValue(i));
224  }
225  msg_analog.header.stamp = ros::Time::now();
226  msg_analog.uri = names;
227  msg_analog.value = values;
228 
229  _pubAnalog.publish(msg_analog);
230 }
231 
232 auto PhidgetIKROS::inputChangeHandler(int index, int inputState) -> int
233 {
234  ROS_DEBUG("Board %s: Digital Input %d changed to State: %d", _board_name.c_str(), index, inputState);
235  cob_phidgets::DigitalSensor msg;
236  std::vector<std::string> names;
237  std::vector<signed char> states;
238 
239  std::string name;
242  name = (*_indexNameMapItr).second;
243  names.push_back(name);
244  states.push_back(inputState);
245 
246  msg.header.stamp = ros::Time::now();
247  msg.uri = names;
248  msg.state = states;
249  _pubDigital.publish(msg);
250 
251  return 0;
252 }
253 
254 auto PhidgetIKROS::outputChangeHandler(int index, int outputState) -> int
255 {
256  ROS_DEBUG("Board %s: Digital Output %d changed to State: %d", _board_name.c_str(), index, outputState);
257  std::lock_guard<std::mutex> lock{_mutex};
258  _outputChanged.updated = true;
259  _outputChanged.index = index;
260  _outputChanged.state = outputState;
261  return 0;
262 }
263 auto PhidgetIKROS::sensorChangeHandler(int index, int sensorValue) -> int
264 {
265  ROS_DEBUG("Board %s: Analog Input %d changed to Value: %d", _board_name.c_str(), index, sensorValue);
266  cob_phidgets::AnalogSensor msg;
267  std::vector<std::string> names;
268  std::vector<short int> values;
269 
270  std::string name;
273  name = (*_indexNameMapItr).second;
274  names.push_back(name);
275  values.push_back(sensorValue);
276 
277  msg.header.stamp = ros::Time::now();
278  msg.uri = names;
279  msg.value = values;
280 
281  _pubAnalog.publish(msg);
282 
283  return 0;
284 }
285 
286 auto PhidgetIKROS::setDigitalOutCallback(cob_phidgets::SetDigitalSensor::Request &req,
287  cob_phidgets::SetDigitalSensor::Response &res) -> bool
288 {
289  bool ret = false;
290  _mutex.lock();
291  _outputChanged.updated=false;
294  _mutex.unlock();
295 
296  // this check is nessesary because [] operator on Maps inserts an element if it is not found
299  {
300  if(this->getOutputState(_indexNameMapDigitalOutRev[req.uri]) == req.state)
301  {
302  ROS_INFO("Digital output %i is already at state %i", _indexNameMapDigitalOutRev[req.uri], req.state);
303  res.uri = req.uri;
304  res.state = req.state;
305  ret = true;
306  }
307  else
308  {
309  ROS_INFO("Setting digital output %i to state %i", _indexNameMapDigitalOutRev[req.uri], req.state);
310  this->setOutputState(_indexNameMapDigitalOutRev[req.uri], req.state);
311 
313  while((ros::Time::now().toSec() - start.toSec()) < 1.0)
314  {
315  _mutex.lock();
316  if(_outputChanged.updated == true)
317  {
318  _mutex.unlock();
319  break;
320  }
321  _mutex.unlock();
322 
323  ros::Duration(0.025).sleep();
324  }
325  _mutex.lock();
327  res.state = _outputChanged.state;
328  ROS_DEBUG("Sending response: updated: %u, index: %d, state: %d",_outputChanged.updated, _outputChanged.index, _outputChanged.state);
330  _mutex.unlock();
331  }
332  }
333  else
334  {
335  ROS_DEBUG("Could not find uri '%s' inside port uri mapping", req.uri.c_str());
336  res.uri = req.uri;
337  res.state = req.state;
338  ret = false;
339  }
340 
341  return ret;
342 }
343 
344 auto PhidgetIKROS::onDigitalOutCallback(const cob_phidgets::DigitalSensorConstPtr& msg) -> void
345 {
346  if(msg->uri.size() == msg->state.size())
347  {
348  for(size_t i = 0; i < msg->uri.size(); i++)
349  {
350  // this check is nessesary because [] operator on Maps inserts an element if it is not found
353  {
354  ROS_INFO("Setting digital output %i to state %i", _indexNameMapDigitalOutRev[msg->uri[i]], msg->state[i]);
355  this->setOutputState(_indexNameMapDigitalOutRev[msg->uri[i]], msg->state[i]);
356  }
357  else
358  ROS_DEBUG("Could not find uri '%s' inside port uri mapping", msg->uri[i].c_str());
359  }
360  }
361  else
362  {
363  ROS_ERROR("Received message with different uri and state container sizes");
364  }
365 }
366 
367 auto PhidgetIKROS::setDataRateCallback(cob_phidgets::SetDataRate::Request &req,
368  cob_phidgets::SetDataRate::Response &res) -> bool
369 {
370  this->setDataRate(req.index, req.data_rate);
371  return true;
372 }
373 auto PhidgetIKROS::setTriggerValueCallback(cob_phidgets::SetTriggerValue::Request &req,
374  cob_phidgets::SetTriggerValue::Response &res) -> bool
375 {
376  this->setSensorChangeTrigger(req.index, req.trigger_value);
377  return true;
378 }
379 
381 {
382  int serialNo, version, numInputs, numOutputs, millis;
383  int numSensors, triggerVal, ratiometric;
384  const char *ptr, *name;
385 
386  CPhidget_getDeviceName((CPhidgetHandle)_iKitHandle, &name);
387  CPhidget_getDeviceType((CPhidgetHandle)_iKitHandle, &ptr);
388  CPhidget_getSerialNumber((CPhidgetHandle)_iKitHandle, &serialNo);
389  CPhidget_getDeviceVersion((CPhidgetHandle)_iKitHandle, &version);
390 
391  CPhidgetInterfaceKit_getInputCount(_iKitHandle, &numInputs);
392  CPhidgetInterfaceKit_getOutputCount(_iKitHandle, &numOutputs);
393  CPhidgetInterfaceKit_getSensorCount(_iKitHandle, &numSensors);
394  CPhidgetInterfaceKit_getRatiometric(_iKitHandle, &ratiometric);
395 
396  ROS_INFO("%s %d attached!!", name, serialNo);
397 
398  ROS_DEBUG("%s", ptr);
399  ROS_DEBUG("Serial Number: %d\tVersion: %d", serialNo, version);
400  ROS_DEBUG("Num Digital Inputs: %d\tNum Digital Outputs: %d", numInputs, numOutputs);
401  ROS_DEBUG("Num Sensors: %d", numSensors);
402  ROS_DEBUG("Ratiometric: %d", ratiometric);
403 
404  for(int i = 0; i < numSensors; i++)
405  {
406  CPhidgetInterfaceKit_getSensorChangeTrigger(_iKitHandle, i, &triggerVal);
407  CPhidgetInterfaceKit_getDataRate(_iKitHandle, i, &millis);
408 
409  ROS_DEBUG("Sensor#: %d > Sensitivity Trigger: %d", i, triggerVal);
410  ROS_DEBUG("Sensor#: %d > Data Rate: %d", i, millis);
411  }
412 
413  return 0;
414 }
415 
417 {
418  int serial_number;
419  const char *device_name;
420 
421  CPhidget_getDeviceName ((CPhidgetHandle)_iKitHandle, &device_name);
422  CPhidget_getSerialNumber((CPhidgetHandle)_iKitHandle, &serial_number);
423  ROS_INFO("%s Serial number %d detached!", device_name, serial_number);
424  return 0;
425 }
auto getInputCount() -> int
Definition: phidgetik.cpp:49
auto readParams(XmlRpc::XmlRpcValue *sensor_params) -> void
std::map< int, std::string > _indexNameMapDigitalOut
Definition: phidgetik_ros.h:65
std::map< std::string, int > _indexNameMapAnalogRev
Definition: phidgetik_ros.h:62
auto setSensorChangeTrigger(int index, int trigger) -> int
Definition: phidgetik.cpp:129
auto inputChangeHandler(int index, int inputState) -> int
ros::Subscriber _subDigital
Definition: phidgetik_ros.h:43
auto getOutputState(int index) -> int
Definition: phidgetik.cpp:77
ROSCPP_DECL void start()
CPhidgetInterfaceKitHandle _iKitHandle
Definition: phidgetik.h:60
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
auto getSensorValue(int index) -> int
Definition: phidgetik.cpp:102
auto waitForAttachment(int timeout) -> int
Definition: phidget.cpp:44
ros::NodeHandle _nh
Definition: phidgetik_ros.h:40
auto setDigitalOutCallback(cob_phidgets::SetDigitalSensor::Request &req, cob_phidgets::SetDigitalSensor::Response &res) -> bool
bool sleep() const
SensingMode
Definition: phidget.h:27
OutputCompare _outputChanged
Definition: phidgetik_ros.h:58
ros::ServiceServer _srvTriggerValue
Definition: phidgetik_ros.h:46
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
#define ROS_WARN(...)
auto update() -> void
ros::Publisher _pubAnalog
Definition: phidgetik_ros.h:41
std::mutex _mutex
Definition: phidgetik_ros.h:59
auto getOutputCount() -> int
Definition: phidgetik.cpp:68
auto detachHandler() -> int
#define ROS_INFO(...)
auto sensorChangeHandler(int index, int sensorValue) -> int
std::map< std::string, int > _indexNameMapDigitalInRev
Definition: phidgetik_ros.h:64
int i
Definition: tablet_leer.c:27
static auto getErrorDescription(int errorCode) -> std::string
Definition: phidget.cpp:96
auto getSensorCount() -> int
Definition: phidgetik.cpp:93
auto setDataRateCallback(cob_phidgets::SetDataRate::Request &req, cob_phidgets::SetDataRate::Response &res) -> bool
auto setDataRate(int index, int datarate) -> int
Definition: phidgetik.cpp:159
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
auto init(int serial_number) -> int
Definition: phidgetik.cpp:44
std::map< int, std::string >::iterator _indexNameMapItr
Definition: phidgetik_ros.h:67
std::map< std::string, int > _indexNameMapDigitalOutRev
Definition: phidgetik_ros.h:66
auto outputChangeHandler(int index, int outputState) -> int
bool hasMember(const std::string &name) const
auto onDigitalOutCallback(const cob_phidgets::DigitalSensorConstPtr &msg) -> void
ros::Publisher _pubDigital
Definition: phidgetik_ros.h:42
ros::ServiceServer _srvDataRate
Definition: phidgetik_ros.h:45
auto attachHandler() -> int
auto getError() -> int
Definition: phidgetik.cpp:182
static Time now()
std::map< int, std::string > _indexNameMapDigitalIn
Definition: phidgetik_ros.h:63
ros::ServiceServer _srvDigitalOut
Definition: phidgetik_ros.h:44
auto setTriggerValueCallback(cob_phidgets::SetTriggerValue::Request &req, cob_phidgets::SetTriggerValue::Response &res) -> bool
auto setOutputState(int index, int state) -> int
Definition: phidgetik.cpp:87
PhidgetIKROS(ros::NodeHandle nh, int serial_num, std::string board_name, XmlRpc::XmlRpcValue *sensor_params, SensingMode mode)
#define ROS_ERROR(...)
std::map< int, std::string > _indexNameMapAnalog
Definition: phidgetik_ros.h:61
std::string _board_name
Definition: phidgetik_ros.h:49
auto getInputState(int index) -> int
Definition: phidgetik.cpp:58
std::map< std::string, int >::iterator _indexNameMapRevItr
Definition: phidgetik_ros.h:68
#define ROS_DEBUG(...)


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