RelayNode.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2017, Dataspeed Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Dataspeed Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
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   // Initialize FTDI
00044   ctx_ = ftdi_new();
00045   ftdi_init(ctx_);
00046 
00047   // Get parameters
00048   nh_priv.getParam("serial", param_serial_);
00049   nh_priv.getParam("desc", param_desc_);
00050 
00051   // Setup publishers
00052   pub_ready_ = nh.advertise<std_msgs::Bool>("ready", 1, true);
00053   pub_serial_ = nh.advertise<std_msgs::String>("serial", 1, true);
00054 
00055   // Setup subscribers
00056   sub_ = nh.subscribe("relay_cmd", 10, &RelayNode::recv, this);
00057 
00058   // Connect to device
00059   serviceDevice();
00060 
00061   // Setup timer
00062   timer_ = nh.createWallTimer(ros::WallDuration(0.1), &RelayNode::timerCallback, this);
00063 }
00064 
00065 RelayNode::~RelayNode()
00066 {
00067   // De-initialize FTDI
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 } // namespace sainsmart_relay_usb
00143 


sainsmart_relay_usb
Author(s): Kevin Hallenbeck
autogenerated on Thu Jun 6 2019 19:05:14