Go to the documentation of this file.
33 #include <std_msgs/Float64.h>
37 #include "phidgets_msgs/SetAnalogOutput.h"
43 : nh_(nh), nh_private_(nh_private)
45 ROS_INFO(
"Starting Phidgets Analog 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 AnalogOutputs serial %d, hub port %d ...",
74 serial_num, hub_port);
78 aos_ = std::make_unique<AnalogOutputs>(serial_num, hub_port,
87 int n_out =
aos_->getOutputCount();
88 ROS_INFO(
"Connected %d outputs", n_out);
90 for (
int i = 0; i < n_out; i++)
92 char topicname[] =
"analog_output00";
93 snprintf(topicname,
sizeof(topicname),
"analog_output%02d", i);
95 std::make_unique<AnalogOutputSetter>(
aos_.get(), i, nh, topicname);
102 phidgets_msgs::SetAnalogOutput::Request& req,
103 phidgets_msgs::SetAnalogOutput::Response& res)
105 aos_->setOutputVoltage(req.index, req.voltage);
112 const std::string& topicname)
113 : aos_(aos), index_(index)
AnalogOutputSetter(AnalogOutputs *aos, int index, ros::NodeHandle nh, const std::string &topicname)
void setMsgCallback(const std_msgs::Float64::ConstPtr &msg)
void setOutputVoltage(int index, double voltage) const
std::vector< std::unique_ptr< AnalogOutputSetter > > out_subs_
bool getParam(const std::string &key, bool &b) const
std::unique_ptr< AnalogOutputs > aos_
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
AnalogOutputsRosI(ros::NodeHandle nh, ros::NodeHandle nh_private)
ros::Subscriber subscription_
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())
const char * what() const noexcept
bool setSrvCallback(phidgets_msgs::SetAnalogOutput::Request &req, phidgets_msgs::SetAnalogOutput::Response &res)
ros::ServiceServer out_srv_