Go to the documentation of this file.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
00036
00037 #include <stdio.h>
00038 #include <string.h>
00039 #include <errno.h>
00040 #include <termios.h>
00041 #include <math.h>
00042 #include <poll.h>
00043 #include <signal.h>
00044 #include <fcntl.h>
00045 #include <iostream>
00046 #include <fstream>
00047
00048 #include "CANUSB.h"
00049
00050 #include <ros/ros.h>
00051
00052 CANUSB::CANUSB(std::string * serial_port_name, boost::function<void(std::string*)> f) : serial_port_()
00053 {
00054 open_ = false;
00055
00056 try{ serial_port_.open((char*)serial_port_name->c_str(), 115200); }
00057 catch(cereal::Exception& e)
00058 {
00059 ROS_FATAL("CANUSB - %s - Failed to open the serial port!!!", __FUNCTION__);
00060 ROS_BREAK();
00061 }
00062
00063 receivedFrameCallback = f;
00064 }
00065
00066 CANUSB::~CANUSB()
00067 {
00068 closeCANBus();
00069
00070 serial_port_.close();
00071 }
00072
00073 bool CANUSB::openCANBus(CANUSB_BitRate bit_rate)
00074 {
00075 if(open_) return false;
00076
00077
00078 if( !setCANBitRate(bit_rate) )
00079 {
00080 ROS_ERROR("CANUSB - %s - Failed to set bit rate!", __FUNCTION__);
00081 return false;
00082 }
00083
00084 char msg[3];
00085
00086 msg[0] = 'O';
00087 msg[1] = CANUSB_OK;
00088 msg[2] = 0;
00089
00090
00091 try{ serial_port_.write(msg); }
00092 catch(cereal::Exception& e)
00093 {
00094 ROS_ERROR("CANUSB - %s - Failed to send open message!", __FUNCTION__);
00095 return false;
00096 }
00097
00098
00099 char reply;
00100 serial_port_.read(&reply, 1);
00101 if(reply != CANUSB_OK) return false;
00102
00103 open_ = true;
00104
00105
00106
00107
00108
00109
00110
00111
00112
00113 if( !serial_port_.startReadBetweenStream(boost::bind(&CANUSB::newFrameCallback, this, _1), 't', CANUSB_OK) )
00114 {
00115 closeCANBus();
00116 ROS_ERROR("CANUSB - %s - Failed to start streaming data!", __FUNCTION__);
00117 return false;
00118 }
00119
00120 return true;
00121 }
00122
00123 bool CANUSB::closeCANBus()
00124 {
00125 if(!open_) return false;
00126
00127 serial_port_.stopStream();
00128
00129 char msg[3];
00130
00131 msg[0] = 'C';
00132 msg[1] = CANUSB_OK;
00133 msg[2] = 0;
00134
00135 try{ serial_port_.write(msg); }
00136 catch(cereal::Exception& e)
00137 {
00138 ROS_ERROR("CANUSB - %s - Failed to send close msg!", __FUNCTION__);
00139 return false;
00140 }
00141
00142
00143 char reply;
00144 serial_port_.read(&reply, 1);
00145 if(reply == CANUSB_OK)
00146 {
00147 open_ = false;
00148 return true;
00149 }
00150
00151 ROS_ERROR("CANUSB - %s - Did not get reply - %d", __FUNCTION__, (int)reply);
00152 return false;
00153 }
00154
00155 bool CANUSB::reset()
00156 {
00157 if(open_) return false;
00158
00159 char msg[3];
00160
00161 msg[0] = 'R';
00162 msg[1] = CANUSB_OK;
00163 msg[2] = 0;
00164
00165 try{ serial_port_.write(msg); }
00166 catch(cereal::Exception& e)
00167 {
00168 ROS_ERROR("CANUSB - %s - Failed to send reset msg!", __FUNCTION__);
00169 return false;
00170 }
00171
00172
00173 char reply;
00174 serial_port_.read(&reply, 1);
00175 if(reply == CANUSB_OK) return true;
00176
00177 ROS_ERROR("CANUSB - %s - Did not get reply - %d", __FUNCTION__, (int)reply);
00178 return false;
00179 }
00180
00181 bool CANUSB::setCANBitRate(CANUSB_BitRate bit_rate)
00182 {
00183 if(open_) return false;
00184
00185 char msg[4];
00186
00187 msg[0] = 'S';
00188 msg[1] = bit_rate+48;
00189 msg[2] = CANUSB_OK;
00190 msg[3] = 0;
00191
00192 try{ serial_port_.write(msg); }
00193 catch(cereal::Exception& e)
00194 {
00195 ROS_INFO("CANUSB - %s - Unable to send bit rate!", __FUNCTION__);
00196 return false;
00197 }
00198
00199
00200 char reply;
00201 serial_port_.read(&reply, 1);
00202 if(reply == CANUSB_OK) return true;
00203
00204 ROS_ERROR("CANUSB - %s - Did not get reply - %d", __FUNCTION__, (int)reply);
00205 return false;
00206 }
00207
00208 bool CANUSB::transmitStandardFrame(std::string * frame)
00209 {
00210 if(!open_) return false;
00211
00212 char ok[2];
00213 ok[0] = CANUSB_OK;
00214 ok[1] = 0;
00215
00216 std::string msg;
00217
00218 msg = "t";
00219 msg.append(*frame);
00220 msg.append(ok);
00221
00222 serial_port_.pauseStream();
00223
00224 try{ serial_port_.write(msg.c_str()); }
00225 catch(cereal::Exception& e)
00226 {
00227 return false;
00228 }
00229
00230
00231 char reply;
00232 serial_port_.read(&reply, 1);
00233
00234 serial_port_.resumeStream();
00235
00236 if(reply == 'z') return true;
00237
00238 ROS_ERROR("CANUSB - %s - Did not get reply - %d", __FUNCTION__, (int)reply);
00239 return false;
00240 }
00241
00242
00243 bool CANUSB::transmitExtendedFrame(std::string * frame)
00244 {
00245 if(!open_) return false;
00246
00247 return false;
00248 }
00249
00250
00251 int CANUSB::getVersion()
00252 {
00253 if(open_) return false;
00254
00255 return 0;
00256 }
00257
00258
00259 int CANUSB::getSerialNumber()
00260 {
00261 if(open_) return false;
00262
00263 return 0;
00264 }
00265
00266 void CANUSB::newFrameCallback(std::string * frame)
00267 {
00268 receivedFrameCallback(frame);
00269 }
00270
00271