78 uint8_t value = msg->data;
79 int ret = ftdi_write_data(
ctx_, &value,
sizeof(value));
80 if (ret ==
sizeof(value)) {
95 struct ftdi_device_list *devlist;
96 if (ftdi_usb_find_all(
ctx_, &devlist, 0x0403, 0x6001) >= 0) {
97 struct ftdi_device_list *curdev;
98 char buf_manu[128], buf_desc[128], buf_serial[128];
99 for (curdev = devlist; curdev != NULL; curdev = curdev->next) {
100 if (ftdi_usb_get_strings(
ctx_, curdev->dev, buf_manu, 128, buf_desc, 128, buf_serial, 128) >= 0) {
103 if (ftdi_usb_open_dev(
ctx_, curdev->dev) >= 0) {
104 if (ftdi_set_bitmode(
ctx_, -1, BITMODE_BITBANG) >= 0) {
105 ROS_INFO(
"Opened device %s %s %s", buf_manu, buf_desc, buf_serial);
112 ftdi_usb_close(
ctx_);
119 ftdi_list_free(&devlist);
122 unsigned char buf[64] = {0};
123 int ret = ftdi_read_data(
ctx_, buf,
sizeof(buf));
124 if (ret !=
sizeof(buf)) {
126 ftdi_usb_close(
ctx_);
ros::Publisher pub_serial_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void timerCallback(const ros::WallTimerEvent &event)
std::string param_serial_
WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void recv(const std_msgs::Byte::ConstPtr &msg)
void publishSerial(const std::string &serial)
bool getParam(const std::string &key, std::string &s) const
ros::Publisher pub_ready_
RelayNode(ros::NodeHandle &nh, ros::NodeHandle &nh_priv)
void publishReady(bool ready)