00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include "RelayNode.h"
00036 #include <ftdi.h>
00037
00038 namespace sainsmart_relay_usb
00039 {
00040
00041 RelayNode::RelayNode(ros::NodeHandle &nh, ros::NodeHandle &nh_priv) : open_(false)
00042 {
00043
00044 ctx_ = ftdi_new();
00045 ftdi_init(ctx_);
00046
00047
00048 nh_priv.getParam("serial", param_serial_);
00049 nh_priv.getParam("desc", param_desc_);
00050
00051
00052 pub_ready_ = nh.advertise<std_msgs::Bool>("ready", 1, true);
00053 pub_serial_ = nh.advertise<std_msgs::String>("serial", 1, true);
00054
00055
00056 sub_ = nh.subscribe("relay_cmd", 10, &RelayNode::recv, this);
00057
00058
00059 serviceDevice();
00060
00061
00062 timer_ = nh.createWallTimer(ros::WallDuration(0.1), &RelayNode::timerCallback, this);
00063 }
00064
00065 RelayNode::~RelayNode()
00066 {
00067
00068 if (ctx_) {
00069 ftdi_deinit(ctx_);
00070 ftdi_free(ctx_);
00071 ctx_ = NULL;
00072 }
00073 }
00074
00075 void RelayNode::recv(const std_msgs::Byte::ConstPtr& msg)
00076 {
00077 if (open_) {
00078 uint8_t value = msg->data;
00079 int ret = ftdi_write_data(ctx_, &value, sizeof(value));
00080 if (ret == sizeof(value)) {
00081 ROS_INFO("FTDI %s: Writing 0x%02X", serial_live_.c_str(), value);
00082 } else {
00083 ROS_WARN("FTDI %s: Writing 0x%02X failed, %i: %s", serial_live_.c_str(), value, ret, ftdi_get_error_string(ctx_));
00084 ftdi_usb_close(ctx_);
00085 open_ = false;
00086 publishReady(false);
00087 }
00088 }
00089 }
00090
00091 void RelayNode::serviceDevice()
00092 {
00093 if (!open_) {
00094 int ret = 0;
00095 struct ftdi_device_list *devlist;
00096 if (ftdi_usb_find_all(ctx_, &devlist, 0x0403, 0x6001) >= 0) {
00097 struct ftdi_device_list *curdev;
00098 char buf_manu[128], buf_desc[128], buf_serial[128];
00099 for (curdev = devlist; curdev != NULL; curdev = curdev->next) {
00100 if (ftdi_usb_get_strings(ctx_, curdev->dev, buf_manu, 128, buf_desc, 128, buf_serial, 128) >= 0) {
00101 if (!param_serial_.length() || (param_serial_ == std::string(buf_serial))) {
00102 if (!param_desc_.length() || (param_desc_ == std::string(buf_desc))) {
00103 if (ftdi_usb_open_dev(ctx_, curdev->dev) >= 0) {
00104 if (ftdi_set_bitmode(ctx_, -1, BITMODE_BITBANG) >= 0) {
00105 ROS_INFO("Opened device %s %s %s", buf_manu, buf_desc, buf_serial);
00106 serial_live_ = buf_serial;
00107 open_ = true;
00108 publishSerial(serial_live_);
00109 publishReady(true);
00110 break;
00111 } else {
00112 ftdi_usb_close(ctx_);
00113 }
00114 }
00115 }
00116 }
00117 }
00118 }
00119 ftdi_list_free(&devlist);
00120 }
00121 } else {
00122 unsigned char buf[64] = {0};
00123 int ret = ftdi_read_data(ctx_, buf, sizeof(buf));
00124 if (ret != sizeof(buf)) {
00125 ROS_WARN("FTDI %s: Disconnected, %i: %s", serial_live_.c_str(), ret, ftdi_get_error_string(ctx_));
00126 ftdi_usb_close(ctx_);
00127 open_ = false;
00128 publishReady(false);
00129 } else {
00130 #if 0
00131 ROS_INFO("FTDI %s: Ping, %i: %s", serial_live_.c_str(), ret, ftdi_get_error_string(ctx_));
00132 #endif
00133 }
00134 }
00135 }
00136
00137 void RelayNode::timerCallback(const ros::WallTimerEvent& event)
00138 {
00139 serviceDevice();
00140 }
00141
00142 }
00143