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;
77 else if(type ==
"digital_in")
79 else if(type ==
"digital_out")
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);
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);
102 for(
int i = 0;
i < count;
i++)
107 std::stringstream ss;
113 for(
int i = 0;
i < count;
i++)
118 std::stringstream ss;
124 for(
int i = 0;
i < count;
i++)
129 std::stringstream ss;
137 for(
int i = 0;
i < count;
i++)
142 std::stringstream ss;
149 for(
int i = 0;
i < count;
i++)
158 for(
int i = 0;
i < count;
i++)
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++)
181 name = (*_indexNameMapItr).second;
182 names.push_back(name);
186 msg_digit.uri = names;
187 msg_digit.state = states;
195 for(
int i = 0;
i < count;
i++)
200 name = (*_indexNameMapItr).second;
201 names.push_back(name);
205 msg_digit.uri = names;
206 msg_digit.state = states;
212 cob_phidgets::AnalogSensor msg_analog;
214 std::vector<short int> values;
216 for(
int i = 0;
i < count;
i++)
221 name = (*_indexNameMapItr).second;
222 names.push_back(name);
226 msg_analog.uri = names;
227 msg_analog.value = values;
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;
242 name = (*_indexNameMapItr).second;
243 names.push_back(name);
244 states.push_back(inputState);
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};
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;
273 name = (*_indexNameMapItr).second;
274 names.push_back(name);
275 values.push_back(sensorValue);
287 cob_phidgets::SetDigitalSensor::Response &res) ->
bool 304 res.state = req.state;
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++)
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 374 cob_phidgets::SetTriggerValue::Response &res) ->
bool 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);
auto getInputCount() -> int
auto readParams(XmlRpc::XmlRpcValue *sensor_params) -> void
std::map< int, std::string > _indexNameMapDigitalOut
std::map< std::string, int > _indexNameMapAnalogRev
auto setSensorChangeTrigger(int index, int trigger) -> int
auto inputChangeHandler(int index, int inputState) -> int
ros::Subscriber _subDigital
auto getOutputState(int index) -> int
CPhidgetInterfaceKitHandle _iKitHandle
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
auto waitForAttachment(int timeout) -> int
auto setDigitalOutCallback(cob_phidgets::SetDigitalSensor::Request &req, cob_phidgets::SetDigitalSensor::Response &res) -> bool
OutputCompare _outputChanged
ros::ServiceServer _srvTriggerValue
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros::Publisher _pubAnalog
auto getOutputCount() -> int
auto detachHandler() -> int
auto sensorChangeHandler(int index, int sensorValue) -> int
std::map< std::string, int > _indexNameMapDigitalInRev
static auto getErrorDescription(int errorCode) -> std::string
auto getSensorCount() -> int
auto setDataRateCallback(cob_phidgets::SetDataRate::Request &req, cob_phidgets::SetDataRate::Response &res) -> bool
auto setDataRate(int index, int datarate) -> int
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
auto init(int serial_number) -> int
std::map< int, std::string >::iterator _indexNameMapItr
std::map< std::string, int > _indexNameMapDigitalOutRev
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
ros::ServiceServer _srvDataRate
auto attachHandler() -> int
std::map< int, std::string > _indexNameMapDigitalIn
ros::ServiceServer _srvDigitalOut
auto setTriggerValueCallback(cob_phidgets::SetTriggerValue::Request &req, cob_phidgets::SetTriggerValue::Response &res) -> bool
auto setOutputState(int index, int state) -> int
PhidgetIKROS(ros::NodeHandle nh, int serial_num, std::string board_name, XmlRpc::XmlRpcValue *sensor_params, SensingMode mode)
std::map< int, std::string > _indexNameMapAnalog
auto getInputState(int index) -> int
std::map< std::string, int >::iterator _indexNameMapRevItr