35 #include <std_msgs/Bool.h>
44 : nh_(nh), nh_private_(nh_private)
46 ROS_INFO(
"Starting Phidgets DigitalInputs");
54 if (!nh_private.
getParam(
"hub_port", hub_port))
58 bool is_hub_port_device;
59 if (!nh_private.
getParam(
"is_hub_port_device", is_hub_port_device))
62 is_hub_port_device =
false;
78 ROS_INFO(
"Connecting to Phidgets DigitalInputs serial %d, hub port %d ...",
79 serial_num, hub_port);
84 std::lock_guard<std::mutex> lock(
di_mutex_);
89 dis_ = std::make_unique<DigitalInputs>(
90 serial_num, hub_port, is_hub_port_device,
92 std::placeholders::_1, std::placeholders::_2));
94 n_in =
dis_->getInputCount();
95 ROS_INFO(
"Connected %d inputs", n_in);
97 for (
int i = 0; i < n_in; i++)
99 char topicname[] =
"digital_input00";
100 snprintf(topicname,
sizeof(topicname),
"digital_input%02d", i);
120 for (
int i = 0; i < n_in; ++i)
136 std::lock_guard<std::mutex> lock(
di_mutex_);
137 for (
int i = 0; i < static_cast<int>(
val_to_pubs_.size()); ++i)
147 std::lock_guard<std::mutex> lock(
di_mutex_);