23 #include "std_msgs/Bool.h" 24 #include "sensor_msgs/Range.h" 26 #include <libphidgets/phidget21.h> 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)
46 pub_range_.
publish((sensor_msgs::Range) *
this);
49 operator sensor_msgs::Range()
const 51 sensor_msgs::Range msg;
54 msg.radiation_type = sensor_msgs::Range::INFRARED;
57 msg.field_of_view = 0;
60 for (std::list<int>::const_iterator it = vals_.begin();
61 it != vals_.end(); it++)
66 msg.range = 20.76 / (sum / (double) num - 11.);
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);
99 ROS_INFO(
"Version: %8d SerialNumber: %10d", version, sernum);
112 int Index,
int Value)
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);
121 int main(
int argc,
char **argv)
126 std::vector<Sensor> g_sensors;
130 nh_.
param(
"sensors", v, v);
131 for (
int i = 0;
i < v.
size();
i++)
136 std::string fr_id = v[
i][1];
137 int filter = v.
size() > 2 ? (int) v[
i][2] : 10;
139 g_sensors.push_back(
Sensor(fr_id,
id, filter));
144 ROS_ERROR(
"Parameter sensors not set, shutting down node...");
152 int numInputs, numOutputs, numSensors;
155 CPhidgetInterfaceKitHandle IFK = 0;
156 CPhidget_enableLogging(PHIDGET_LOG_VERBOSE, NULL);
157 CPhidgetInterfaceKit_create(&IFK);
158 CPhidgetInterfaceKit_set_OnSensorChange_Handler(IFK,
163 CPhidget_open((CPhidgetHandle) IFK, -1);
166 ROS_INFO(
"waiting for phidgets attachement...");
167 if ((err = CPhidget_waitForAttachment((CPhidgetHandle) IFK, 10000))
171 CPhidget_getErrorDescription(err, &errStr);
172 ROS_ERROR(
"Error waiting for attachment: (%d): %s", err, errStr);
178 CPhidgetInterfaceKit_getOutputCount((CPhidgetInterfaceKitHandle) IFK,
180 CPhidgetInterfaceKit_getInputCount((CPhidgetInterfaceKitHandle) IFK,
182 CPhidgetInterfaceKit_getSensorCount((CPhidgetInterfaceKitHandle) IFK,
187 "Sensors:%d Inputs:%d Outputs:%d", numSensors, numInputs, numOutputs);
191 for (
size_t i = 0;
i < g_sensors.size();
i++)
197 exit: CPhidget_close((CPhidgetHandle) IFK);
198 CPhidget_delete((CPhidgetHandle) IFK);
int main(int argc, char **argv)
int IFK_AttachHandler(CPhidgetHandle IFK, void *userptr)
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Sensor(const std::string &fr_id, const int id, const int filter_size=10)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
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 hasParam(const std::string &key) const
ROSCPP_DECL void spinOnce()
ros::Publisher pub_range_