RelayNode.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Dataspeed Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Dataspeed Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #include "RelayNode.h"
36 #include <ftdi.h>
37 
39 {
40 
42 {
43  // Initialize FTDI
44  ctx_ = ftdi_new();
45  ftdi_init(ctx_);
46 
47  // Get parameters
48  nh_priv.getParam("serial", param_serial_);
49  nh_priv.getParam("desc", param_desc_);
50 
51  // Setup publishers
52  pub_ready_ = nh.advertise<std_msgs::Bool>("ready", 1, true);
53  pub_serial_ = nh.advertise<std_msgs::String>("serial", 1, true);
54 
55  // Setup subscribers
56  sub_ = nh.subscribe("relay_cmd", 10, &RelayNode::recv, this);
57 
58  // Connect to device
59  serviceDevice();
60 
61  // Setup timer
63 }
64 
66 {
67  // De-initialize FTDI
68  if (ctx_) {
69  ftdi_deinit(ctx_);
70  ftdi_free(ctx_);
71  ctx_ = NULL;
72  }
73 }
74 
75 void RelayNode::recv(const std_msgs::Byte::ConstPtr& msg)
76 {
77  if (open_) {
78  uint8_t value = msg->data;
79  int ret = ftdi_write_data(ctx_, &value, sizeof(value));
80  if (ret == sizeof(value)) {
81  ROS_DEBUG("FTDI %s: Writing 0x%02X", serial_live_.c_str(), value);
82  } else {
83  ROS_WARN("FTDI %s: Writing 0x%02X failed, %i: %s", serial_live_.c_str(), value, ret, ftdi_get_error_string(ctx_));
84  ftdi_usb_close(ctx_);
85  open_ = false;
86  publishReady(false);
87  }
88  }
89 }
90 
92 {
93  if (!open_) {
94  int ret = 0;
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) {
101  if (!param_serial_.length() || (param_serial_ == std::string(buf_serial))) {
102  if (!param_desc_.length() || (param_desc_ == std::string(buf_desc))) {
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);
106  serial_live_ = buf_serial;
107  open_ = true;
109  publishReady(true);
110  break;
111  } else {
112  ftdi_usb_close(ctx_);
113  }
114  }
115  }
116  }
117  }
118  }
119  ftdi_list_free(&devlist);
120  }
121  } else {
122  unsigned char buf[64] = {0};
123  int ret = ftdi_read_data(ctx_, buf, sizeof(buf));
124  if (ret != sizeof(buf)) {
125  ROS_WARN("FTDI %s: Disconnected, %i: %s", serial_live_.c_str(), ret, ftdi_get_error_string(ctx_));
126  ftdi_usb_close(ctx_);
127  open_ = false;
128  publishReady(false);
129  } else {
130 #if 0
131  ROS_INFO("FTDI %s: Ping, %i: %s", serial_live_.c_str(), ret, ftdi_get_error_string(ctx_));
132 #endif
133  }
134  }
135 }
136 
138 {
139  serviceDevice();
140 }
141 
142 } // namespace sainsmart_relay_usb
143 
ros::Publisher pub_serial_
Definition: RelayNode.h:83
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)
Definition: RelayNode.cpp:137
#define ROS_WARN(...)
#define ROS_INFO(...)
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)
Definition: RelayNode.cpp:75
void publishSerial(const std::string &serial)
Definition: RelayNode.h:63
bool getParam(const std::string &key, std::string &s) const
RelayNode(ros::NodeHandle &nh, ros::NodeHandle &nh_priv)
Definition: RelayNode.cpp:41
void publishReady(bool ready)
Definition: RelayNode.h:59
#define ROS_DEBUG(...)


sainsmart_relay_usb
Author(s): Kevin Hallenbeck
autogenerated on Fri Feb 5 2021 03:33:42