Go to the documentation of this file.
33 #include <std_msgs/Bool.h>
37 #include "phidgets_msgs/SetDigitalOutput.h"
43 : nh_(nh), nh_private_(nh_private)
45 ROS_INFO(
"Starting Phidgets Digital Outputs");
53 if (!nh_private.
getParam(
"hub_port", hub_port))
57 bool is_hub_port_device;
58 if (!nh_private.
getParam(
"is_hub_port_device", is_hub_port_device))
61 is_hub_port_device =
false;
73 ROS_INFO(
"Connecting to Phidgets DigitalOutputs serial %d, hub port %d ...",
74 serial_num, hub_port);
78 dos_ = std::make_unique<DigitalOutputs>(serial_num, hub_port,
87 int n_out =
dos_->getOutputCount();
88 ROS_INFO(
"Connected %d outputs", n_out);
90 for (
int i = 0; i < n_out; i++)
92 char topicname[] =
"digital_output00";
93 snprintf(topicname,
sizeof(topicname),
"digital_output%02d", i);
95 std::make_unique<DigitalOutputSetter>(
dos_.get(), i, nh, topicname);
102 phidgets_msgs::SetDigitalOutput::Request& req,
103 phidgets_msgs::SetDigitalOutput::Response& res)
105 dos_->setOutputState(req.index, req.state);
112 const std::string& topicname)
113 : dos_(dos), index_(index)
ros::NodeHandle nh_private_
bool getParam(const std::string &key, bool &b) const
void setMsgCallback(const std_msgs::Bool::ConstPtr &msg)
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
std::unique_ptr< DigitalOutputs > dos_
ros::ServiceServer out_srv_
DigitalOutputsRosI(ros::NodeHandle nh, ros::NodeHandle nh_private)
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())
ros::Subscriber subscription_
std::vector< std::unique_ptr< DigitalOutputSetter > > out_subs_
const char * what() const noexcept
bool setSrvCallback(phidgets_msgs::SetDigitalOutput::Request &req, phidgets_msgs::SetDigitalOutput::Response &res)
DigitalOutputSetter(DigitalOutputs *dos, int index, ros::NodeHandle nh, const std::string &topicname)
void setOutputState(int index, bool state) const