digital_inputs_ros_i.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019, Open Source Robotics Foundation
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <functional>
31 #include <memory>
32 #include <mutex>
33 
34 #include <ros/ros.h>
35 #include <std_msgs/Bool.h>
36 
39 
40 namespace phidgets {
41 
43  ros::NodeHandle nh_private)
44  : nh_(nh), nh_private_(nh_private)
45 {
46  ROS_INFO("Starting Phidgets DigitalInputs");
47 
48  int serial_num;
49  if (!nh_private_.getParam("serial", serial_num))
50  {
51  serial_num = -1; // default open any device
52  }
53  int hub_port;
54  if (!nh_private.getParam("hub_port", hub_port))
55  {
56  hub_port = 0; // only used if the device is on a VINT hub_port
57  }
58  bool is_hub_port_device;
59  if (!nh_private.getParam("is_hub_port_device", is_hub_port_device))
60  {
61  // only used if the device is on a VINT hub_port
62  is_hub_port_device = false;
63  }
64  if (!nh_private.getParam("publish_rate", publish_rate_))
65  {
66  publish_rate_ = 0;
67  }
68  if (nh_private.getParam("server_name", server_name_) &&
69  nh_private.getParam("server_ip", server_ip_))
70  {
71  PhidgetNet_addServer(server_name_.c_str(), server_ip_.c_str(), 5661, "",
72  0);
73 
74  ROS_INFO("Using phidget server %s at IP %s", server_name_.c_str(),
75  server_ip_.c_str());
76  }
77 
78  ROS_INFO("Connecting to Phidgets DigitalInputs serial %d, hub port %d ...",
79  serial_num, hub_port);
80 
81  // We take the mutex here and don't unlock until the end of the constructor
82  // to prevent a callback from trying to use the publisher before we are
83  // finished setting up.
84  std::lock_guard<std::mutex> lock(di_mutex_);
85 
86  int n_in;
87  try
88  {
89  dis_ = std::make_unique<DigitalInputs>(
90  serial_num, hub_port, is_hub_port_device,
92  std::placeholders::_1, std::placeholders::_2));
93 
94  n_in = dis_->getInputCount();
95  ROS_INFO("Connected %d inputs", n_in);
96  val_to_pubs_.resize(n_in);
97  for (int i = 0; i < n_in; i++)
98  {
99  char topicname[] = "digital_input00";
100  snprintf(topicname, sizeof(topicname), "digital_input%02d", i);
101  val_to_pubs_[i].pub = nh_.advertise<std_msgs::Bool>(topicname, 1);
102  val_to_pubs_[i].last_val = dis_->getInputValue(i);
103  }
104  } catch (const Phidget22Error& err)
105  {
106  ROS_ERROR("DigitalInputs: %s", err.what());
107  throw;
108  }
109 
110  if (publish_rate_ > 0)
111  {
114  } else
115  {
116  // If we are *not* publishing periodically, then we are event driven and
117  // will only publish when something changes (where "changes" is defined
118  // by the libphidget22 library). In that case, make sure to publish
119  // once at the beginning to make sure there is *some* data.
120  for (int i = 0; i < n_in; ++i)
121  {
122  publishLatest(i);
123  }
124  }
125 }
126 
128 {
129  std_msgs::Bool msg;
130  msg.data = val_to_pubs_[index].last_val;
131  val_to_pubs_[index].pub.publish(msg);
132 }
133 
135 {
136  std::lock_guard<std::mutex> lock(di_mutex_);
137  for (int i = 0; i < static_cast<int>(val_to_pubs_.size()); ++i)
138  {
139  publishLatest(i);
140  }
141 }
142 
143 void DigitalInputsRosI::stateChangeCallback(int index, int input_value)
144 {
145  if (static_cast<int>(val_to_pubs_.size()) > index)
146  {
147  std::lock_guard<std::mutex> lock(di_mutex_);
148  val_to_pubs_[index].last_val = input_value == 0;
149 
150  if (publish_rate_ <= 0)
151  {
152  publishLatest(index);
153  }
154  }
155 }
156 
157 } // namespace phidgets
phidgets
phidgets::DigitalInputsRosI::timer_
ros::Timer timer_
Definition: digital_inputs_ros_i.h:61
phidgets::DigitalInputsRosI::nh_private_
ros::NodeHandle nh_private_
Definition: digital_inputs_ros_i.h:59
phidgets::DigitalInputsRosI::dis_
std::unique_ptr< DigitalInputs > dis_
Definition: digital_inputs_ros_i.h:54
digital_inputs_ros_i.h
phidgets::DigitalInputsRosI::val_to_pubs_
std::vector< ValToPub > val_to_pubs_
Definition: digital_inputs_ros_i.h:56
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
phidgets::DigitalInputsRosI::timerCallback
void timerCallback(const ros::TimerEvent &event)
Definition: digital_inputs_ros_i.cpp:134
phidgets::Phidget22Error
digital_inputs.h
ros::TimerEvent
phidgets::DigitalInputsRosI::server_name_
std::string server_name_
Definition: digital_inputs_ros_i.h:63
phidgets::DigitalInputsRosI::di_mutex_
std::mutex di_mutex_
Definition: digital_inputs_ros_i.h:55
phidgets::Phidget22Error::what
const char * what() const noexcept
phidgets::DigitalInputsRosI::nh_
ros::NodeHandle nh_
Definition: digital_inputs_ros_i.h:58
phidgets::DigitalInputsRosI::DigitalInputsRosI
DigitalInputsRosI(ros::NodeHandle nh, ros::NodeHandle nh_private)
Definition: digital_inputs_ros_i.cpp:42
phidgets::DigitalInputsRosI::publish_rate_
int publish_rate_
Definition: digital_inputs_ros_i.h:62
ROS_ERROR
#define ROS_ERROR(...)
phidgets::DigitalInputsRosI::publishLatest
void publishLatest(int index)
Definition: digital_inputs_ros_i.cpp:127
ROS_INFO
#define ROS_INFO(...)
phidgets::DigitalInputsRosI::server_ip_
std::string server_ip_
Definition: digital_inputs_ros_i.h:64
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
phidgets::DigitalInputsRosI::stateChangeCallback
void stateChangeCallback(int index, int input_value)
Definition: digital_inputs_ros_i.cpp:143
ros::NodeHandle


phidgets_digital_inputs
Author(s): Chris Lalancette
autogenerated on Sun May 11 2025 02:20:31