digital_outputs_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 <memory>
31 
32 #include <ros/ros.h>
33 #include <std_msgs/Bool.h>
34 
37 #include "phidgets_msgs/SetDigitalOutput.h"
38 
39 namespace phidgets {
40 
42  ros::NodeHandle nh_private)
43  : nh_(nh), nh_private_(nh_private)
44 {
45  ROS_INFO("Starting Phidgets Digital Outputs");
46 
47  int serial_num;
48  if (!nh_private_.getParam("serial", serial_num))
49  {
50  serial_num = -1; // default open any device
51  }
52  int hub_port;
53  if (!nh_private.getParam("hub_port", hub_port))
54  {
55  hub_port = 0; // only used if the device is on a VINT hub_port
56  }
57  bool is_hub_port_device;
58  if (!nh_private.getParam("is_hub_port_device", is_hub_port_device))
59  {
60  // only used if the device is on a VINT hub_port
61  is_hub_port_device = false;
62  }
63  if (nh_private.getParam("server_name", server_name_) &&
64  nh_private.getParam("server_ip", server_ip_))
65  {
66  PhidgetNet_addServer(server_name_.c_str(), server_ip_.c_str(), 5661, "",
67  0);
68 
69  ROS_INFO("Using phidget server %s at IP %s", server_name_.c_str(),
70  server_ip_.c_str());
71  }
72 
73  ROS_INFO("Connecting to Phidgets DigitalOutputs serial %d, hub port %d ...",
74  serial_num, hub_port);
75 
76  try
77  {
78  dos_ = std::make_unique<DigitalOutputs>(serial_num, hub_port,
79  is_hub_port_device);
80 
81  } catch (const Phidget22Error& err)
82  {
83  ROS_ERROR("DigitalOutputs: %s", err.what());
84  throw;
85  }
86 
87  int n_out = dos_->getOutputCount();
88  ROS_INFO("Connected %d outputs", n_out);
89  out_subs_.resize(n_out);
90  for (int i = 0; i < n_out; i++)
91  {
92  char topicname[] = "digital_output00";
93  snprintf(topicname, sizeof(topicname), "digital_output%02d", i);
94  out_subs_[i] =
95  std::make_unique<DigitalOutputSetter>(dos_.get(), i, nh, topicname);
96  }
97  out_srv_ = nh_.advertiseService("set_digital_output",
99 }
100 
102  phidgets_msgs::SetDigitalOutput::Request& req,
103  phidgets_msgs::SetDigitalOutput::Response& res)
104 {
105  dos_->setOutputState(req.index, req.state);
106  res.success = true;
107  return true;
108 }
109 
111  ros::NodeHandle nh,
112  const std::string& topicname)
113  : dos_(dos), index_(index)
114 {
115  subscription_ =
116  nh.subscribe(topicname, 1, &DigitalOutputSetter::setMsgCallback, this);
117 }
118 
119 void DigitalOutputSetter::setMsgCallback(const std_msgs::Bool::ConstPtr& msg)
120 {
121  dos_->setOutputState(index_, msg->data);
122 }
123 
124 } // namespace phidgets
phidgets
phidgets::DigitalOutputsRosI::nh_
ros::NodeHandle nh_
Definition: digital_outputs_ros_i.h:68
phidgets::DigitalOutputsRosI::nh_private_
ros::NodeHandle nh_private_
Definition: digital_outputs_ros_i.h:69
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
phidgets::DigitalOutputSetter::setMsgCallback
void setMsgCallback(const std_msgs::Bool::ConstPtr &msg)
Definition: digital_outputs_ros_i.cpp:119
digital_outputs.h
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
digital_outputs_ros_i.h
phidgets::DigitalOutputSetter::index_
int index_
Definition: digital_outputs_ros_i.h:56
phidgets::DigitalOutputsRosI::dos_
std::unique_ptr< DigitalOutputs > dos_
Definition: digital_outputs_ros_i.h:65
phidgets::DigitalOutputsRosI::server_ip_
std::string server_ip_
Definition: digital_outputs_ros_i.h:72
phidgets::DigitalOutputsRosI::out_srv_
ros::ServiceServer out_srv_
Definition: digital_outputs_ros_i.h:70
phidgets::DigitalOutputsRosI::DigitalOutputsRosI
DigitalOutputsRosI(ros::NodeHandle nh, ros::NodeHandle nh_private)
Definition: digital_outputs_ros_i.cpp:41
phidgets::Phidget22Error
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
phidgets::DigitalOutputSetter::subscription_
ros::Subscriber subscription_
Definition: digital_outputs_ros_i.h:54
phidgets::DigitalOutputsRosI::server_name_
std::string server_name_
Definition: digital_outputs_ros_i.h:71
phidgets::DigitalOutputsRosI::out_subs_
std::vector< std::unique_ptr< DigitalOutputSetter > > out_subs_
Definition: digital_outputs_ros_i.h:66
phidgets::Phidget22Error::what
const char * what() const noexcept
phidgets::DigitalOutputs
phidgets::DigitalOutputSetter::dos_
DigitalOutputs * dos_
Definition: digital_outputs_ros_i.h:55
ROS_ERROR
#define ROS_ERROR(...)
phidgets::DigitalOutputsRosI::setSrvCallback
bool setSrvCallback(phidgets_msgs::SetDigitalOutput::Request &req, phidgets_msgs::SetDigitalOutput::Response &res)
Definition: digital_outputs_ros_i.cpp:101
phidgets::DigitalOutputSetter::DigitalOutputSetter
DigitalOutputSetter(DigitalOutputs *dos, int index, ros::NodeHandle nh, const std::string &topicname)
Definition: digital_outputs_ros_i.cpp:110
ROS_INFO
#define ROS_INFO(...)
phidgets::DigitalOutputs::setOutputState
void setOutputState(int index, bool state) const
ros::NodeHandle


phidgets_digital_outputs
Author(s): Chris Lalancette
autogenerated on Sun May 11 2025 02:20:37