21 :
PhidgetIK(mode), _nh(nh), _serial_num(serial_num), _board_name(board_name)
54 if(sensor_params !=
nullptr)
56 for(
auto& sensor : *sensor_params)
58 std::string name = sensor.first;
62 ROS_ERROR(
"Sensor Param '%s' has no 'type' member. Ignoring param!", name.c_str());
67 ROS_ERROR(
"Sensor Param '%s' has no 'index' member. Ignoring param!", name.c_str());
72 std::string type = value_type;
73 int index = value_index;
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));
82 ROS_ERROR(
"Type '%s' in sensor param '%s' is unkown", type.c_str(), name.c_str());
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);
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);
101 int count = this->getInputCount();
102 for(
int i = 0;
i < count;
i++)
104 _indexNameMapItr = _indexNameMapDigitalIn.find(
i);
105 if(_indexNameMapItr == _indexNameMapDigitalIn.end())
107 std::stringstream ss;
108 ss << _board_name <<
"/" <<
"in/" <<
i;
109 _indexNameMapDigitalIn.insert(std::make_pair(
i, ss.str()));
112 count = this->getOutputCount();
113 for(
int i = 0;
i < count;
i++)
115 _indexNameMapItr = _indexNameMapDigitalOut.find(
i);
116 if(_indexNameMapItr == _indexNameMapDigitalOut.end())
118 std::stringstream ss;
119 ss << _board_name <<
"/" <<
"out/" <<
i;
120 _indexNameMapDigitalOut.insert(std::make_pair(
i, ss.str()));
123 count = this->getSensorCount();
124 for(
int i = 0;
i < count;
i++)
126 _indexNameMapItr = _indexNameMapAnalog.find(
i);
127 if(_indexNameMapItr == _indexNameMapAnalog.end())
129 std::stringstream ss;
130 ss << _board_name <<
"/" <<
i;
131 _indexNameMapAnalog.insert(std::make_pair(
i, ss.str()));
136 count = this->getInputCount();
137 for(
int i = 0;
i < count;
i++)
139 _indexNameMapItr = _indexNameMapDigitalIn.find(
i);
140 if(_indexNameMapItr != _indexNameMapDigitalIn.end())
142 std::stringstream ss;
143 ss << _board_name <<
"/" <<
"in/" <<
i;
145 _indexNameMapDigitalInRev.insert(std::make_pair(_indexNameMapDigitalIn[
i],
i));
148 count = this->getOutputCount();
149 for(
int i = 0;
i < count;
i++)
151 _indexNameMapItr = _indexNameMapDigitalOut.find(
i);
152 if(_indexNameMapItr != _indexNameMapDigitalOut.end())
154 _indexNameMapDigitalOutRev.insert(std::make_pair(_indexNameMapDigitalOut[
i],
i));
157 count = this->getSensorCount();
158 for(
int i = 0;
i < count;
i++)
160 _indexNameMapItr = _indexNameMapAnalog.find(
i);
161 if(_indexNameMapItr != _indexNameMapAnalog.end())
163 _indexNameMapAnalogRev.insert(std::make_pair(_indexNameMapAnalog[
i],
i));
170 int count = this->getInputCount();
171 cob_phidgets::DigitalSensor msg_digit;
172 std::vector<std::string> names;
173 std::vector<signed char> states;
176 for(
int i = 0;
i < count;
i++)
179 _indexNameMapItr = _indexNameMapDigitalIn.find(
i);
180 if(_indexNameMapItr != _indexNameMapDigitalIn.end())
181 name = (*_indexNameMapItr).second;
182 names.push_back(name);
183 states.push_back(this->getInputState(
i));
186 msg_digit.uri = names;
187 msg_digit.state = states;
189 _pubDigital.publish(msg_digit);
194 count = this->getOutputCount();
195 for(
int i = 0;
i < count;
i++)
198 _indexNameMapItr = _indexNameMapDigitalOut.find(
i);
199 if(_indexNameMapItr != _indexNameMapDigitalOut.end())
200 name = (*_indexNameMapItr).second;
201 names.push_back(name);
202 states.push_back(this->getOutputState(
i));
205 msg_digit.uri = names;
206 msg_digit.state = states;
208 _pubDigital.publish(msg_digit);
212 cob_phidgets::AnalogSensor msg_analog;
214 std::vector<short int> values;
215 count = this->getSensorCount();
216 for(
int i = 0;
i < count;
i++)
219 _indexNameMapItr = _indexNameMapAnalog.find(
i);
220 if(_indexNameMapItr != _indexNameMapAnalog.end())
221 name = (*_indexNameMapItr).second;
222 names.push_back(name);
223 values.push_back(this->getSensorValue(
i));
226 msg_analog.uri = names;
227 msg_analog.value = values;
229 _pubAnalog.publish(msg_analog);
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;
240 _indexNameMapItr = _indexNameMapAnalog.find(index);
241 if(_indexNameMapItr != _indexNameMapAnalog.end())
242 name = (*_indexNameMapItr).second;
243 names.push_back(name);
244 states.push_back(inputState);
249 _pubDigital.publish(msg);
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;
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;
271 _indexNameMapItr = _indexNameMapAnalog.find(index);
272 if(_indexNameMapItr != _indexNameMapAnalog.end())
273 name = (*_indexNameMapItr).second;
274 names.push_back(name);
275 values.push_back(sensorValue);
281 _pubAnalog.publish(msg);
287 cob_phidgets::SetDigitalSensor::Response &res) ->
bool
291 _outputChanged.updated=
false;
292 _outputChanged.index=-1;
293 _outputChanged.state=0;
297 _indexNameMapRevItr = _indexNameMapDigitalOutRev.find(req.uri);
298 if(_indexNameMapRevItr != _indexNameMapDigitalOutRev.end())
300 if(this->getOutputState(_indexNameMapDigitalOutRev[req.uri]) == req.state)
302 ROS_INFO(
"Digital output %i is already at state %i", _indexNameMapDigitalOutRev[req.uri], req.state);
304 res.state = req.state;
309 ROS_INFO(
"Setting digital output %i to state %i", _indexNameMapDigitalOutRev[req.uri], req.state);
310 this->setOutputState(_indexNameMapDigitalOutRev[req.uri], req.state);
316 if(_outputChanged.updated ==
true)
326 res.uri = _indexNameMapDigitalOut[_outputChanged.index];
327 res.state = _outputChanged.state;
328 ROS_DEBUG(
"Sending response: updated: %u, index: %d, state: %d",_outputChanged.updated, _outputChanged.index, _outputChanged.state);
329 ret = (_outputChanged.updated && (_outputChanged.index == _indexNameMapDigitalOutRev[req.uri]));
335 ROS_DEBUG(
"Could not find uri '%s' inside port uri mapping", req.uri.c_str());
337 res.state = req.state;
346 if(msg->uri.size() == msg->state.size())
348 for(
size_t i = 0;
i < msg->uri.size();
i++)
351 _indexNameMapRevItr = _indexNameMapDigitalOutRev.find(msg->uri[
i]);
352 if(_indexNameMapRevItr != _indexNameMapDigitalOutRev.end())
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]);
358 ROS_DEBUG(
"Could not find uri '%s' inside port uri mapping", msg->uri[
i].c_str());
363 ROS_ERROR(
"Received message with different uri and state container sizes");
368 cob_phidgets::SetDataRate::Response &res) ->
bool
370 this->setDataRate(req.index, req.data_rate);
374 cob_phidgets::SetTriggerValue::Response &res) ->
bool
376 this->setSensorChangeTrigger(req.index, req.trigger_value);
382 int serialNo, version, numInputs, numOutputs, millis;
383 int numSensors, triggerVal, ratiometric;
384 const char *ptr, *name;
386 CPhidget_getDeviceName((CPhidgetHandle)_iKitHandle, &name);
387 CPhidget_getDeviceType((CPhidgetHandle)_iKitHandle, &ptr);
388 CPhidget_getSerialNumber((CPhidgetHandle)_iKitHandle, &serialNo);
389 CPhidget_getDeviceVersion((CPhidgetHandle)_iKitHandle, &version);
391 CPhidgetInterfaceKit_getInputCount(_iKitHandle, &numInputs);
392 CPhidgetInterfaceKit_getOutputCount(_iKitHandle, &numOutputs);
393 CPhidgetInterfaceKit_getSensorCount(_iKitHandle, &numSensors);
394 CPhidgetInterfaceKit_getRatiometric(_iKitHandle, &ratiometric);
396 ROS_INFO(
"%s %d attached!!", name, serialNo);
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);
404 for(
int i = 0;
i < numSensors;
i++)
406 CPhidgetInterfaceKit_getSensorChangeTrigger(_iKitHandle,
i, &triggerVal);
407 CPhidgetInterfaceKit_getDataRate(_iKitHandle,
i, &millis);
409 ROS_DEBUG(
"Sensor#: %d > Sensitivity Trigger: %d",
i, triggerVal);
410 ROS_DEBUG(
"Sensor#: %d > Data Rate: %d",
i, millis);
419 const char *device_name;
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);