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 #if defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
00020
00021 #include <Arduino.h>
00022
00023
00024 #include "../../include/dynamixel_sdk/port_handler_arduino.h"
00025
00026 #if defined (__OPENCR__)
00027 #define DYNAMIXEL_SERIAL Serial3
00028 #endif
00029
00030 #define LATENCY_TIMER 16 // msec (USB latency timer)
00031
00032 using namespace dynamixel;
00033
00034 PortHandlerArduino::PortHandlerArduino(const char *port_name)
00035 : baudrate_(DEFAULT_BAUDRATE_),
00036 packet_start_time_(0.0),
00037 packet_timeout_(0.0),
00038 tx_time_per_byte(0.0)
00039 {
00040 is_using_ = false;
00041 setPortName(port_name);
00042
00043 #if defined(__OPENCR__)
00044 pinMode(BDPIN_DXL_PWR_EN, OUTPUT);
00045
00046 setPowerOff();
00047 #elif defined(__OPENCM904__)
00048 if (port_name[0] == '1')
00049 {
00050 socket_fd_ = 0;
00051 p_dxl_serial = &Serial1;
00052 }
00053 else if (port_name[0] == '2')
00054 {
00055 socket_fd_ = 1;
00056 p_dxl_serial = &Serial2;
00057 }
00058 else if (port_name[0] == '3')
00059 {
00060 socket_fd_ = 2;
00061 p_dxl_serial = &Serial3;
00062 }
00063 else
00064 {
00065 socket_fd_ = 0;
00066 p_dxl_serial = &Serial1;
00067 }
00068
00069 drv_dxl_begin(socket_fd_);
00070 #endif
00071
00072 setTxDisable();
00073 }
00074
00075 bool PortHandlerArduino::openPort()
00076 {
00077 #if defined(__OPENCR__)
00078 pinMode(BDPIN_DXL_PWR_EN, OUTPUT);
00079
00080 setPowerOn();
00081 delay(1000);
00082 #endif
00083
00084 return setBaudRate(baudrate_);
00085 }
00086
00087 void PortHandlerArduino::closePort()
00088 {
00089 setPowerOff();
00090 }
00091
00092 void PortHandlerArduino::clearPort()
00093 {
00094 #if defined(__OPENCR__)
00095 DYNAMIXEL_SERIAL.flush();
00096 #elif defined(__OPENCM904__)
00097 p_dxl_serial->flush();
00098 #endif
00099 }
00100
00101 void PortHandlerArduino::setPortName(const char *port_name)
00102 {
00103 strcpy(port_name_, port_name);
00104 }
00105
00106 char *PortHandlerArduino::getPortName()
00107 {
00108 return port_name_;
00109 }
00110
00111 bool PortHandlerArduino::setBaudRate(const int baudrate)
00112 {
00113 baudrate_ = checkBaudrateAvailable(baudrate);
00114
00115 if (baudrate_ == -1)
00116 return false;
00117
00118 setupPort(baudrate_);
00119
00120 return true;
00121 }
00122
00123 int PortHandlerArduino::getBaudRate()
00124 {
00125 return baudrate_;
00126 }
00127
00128 int PortHandlerArduino::getBytesAvailable()
00129 {
00130 int bytes_available;
00131
00132 #if defined(__OPENCR__)
00133 bytes_available = DYNAMIXEL_SERIAL.available();
00134 #elif defined(__OPENCM904__)
00135 bytes_available = p_dxl_serial->available();
00136 #endif
00137
00138 return bytes_available;
00139 }
00140
00141 int PortHandlerArduino::readPort(uint8_t *packet, int length)
00142 {
00143 int rx_length;
00144
00145 #if defined(__OPENCR__)
00146 rx_length = DYNAMIXEL_SERIAL.available();
00147 #elif defined(__OPENCM904__)
00148 rx_length = p_dxl_serial->available();
00149 #endif
00150
00151 if (rx_length > length)
00152 rx_length = length;
00153
00154 for (int i = 0; i < rx_length; i++)
00155 {
00156 #if defined(__OPENCR__)
00157 packet[i] = DYNAMIXEL_SERIAL.read();
00158 #elif defined(__OPENCM904__)
00159 packet[i] = p_dxl_serial->read();
00160 #endif
00161 }
00162
00163 return rx_length;
00164 }
00165
00166 int PortHandlerArduino::writePort(uint8_t *packet, int length)
00167 {
00168 int length_written;
00169
00170 setTxEnable();
00171
00172 #if defined(__OPENCR__)
00173 length_written = DYNAMIXEL_SERIAL.write(packet, length);
00174 #elif defined(__OPENCM904__)
00175 length_written = p_dxl_serial->write(packet, length);
00176 #endif
00177
00178 setTxDisable();
00179
00180 return length_written;
00181 }
00182
00183 void PortHandlerArduino::setPacketTimeout(uint16_t packet_length)
00184 {
00185 packet_start_time_ = getCurrentTime();
00186 packet_timeout_ = (tx_time_per_byte * (double)packet_length) + (LATENCY_TIMER * 2.0) + 2.0;
00187 }
00188
00189 void PortHandlerArduino::setPacketTimeout(double msec)
00190 {
00191 packet_start_time_ = getCurrentTime();
00192 packet_timeout_ = msec;
00193 }
00194
00195 bool PortHandlerArduino::isPacketTimeout()
00196 {
00197 if (getTimeSinceStart() > packet_timeout_)
00198 {
00199 packet_timeout_ = 0;
00200 return true;
00201 }
00202
00203 return false;
00204 }
00205
00206 double PortHandlerArduino::getCurrentTime()
00207 {
00208 return (double)millis();
00209 }
00210
00211 double PortHandlerArduino::getTimeSinceStart()
00212 {
00213 double elapsed_time;
00214
00215 elapsed_time = getCurrentTime() - packet_start_time_;
00216 if (elapsed_time < 0.0)
00217 packet_start_time_ = getCurrentTime();
00218
00219 return elapsed_time;
00220 }
00221
00222 bool PortHandlerArduino::setupPort(int baudrate)
00223 {
00224 #if defined(__OPENCR__)
00225 DYNAMIXEL_SERIAL.begin(baudrate);
00226 #elif defined(__OPENCM904__)
00227 p_dxl_serial->setDxlMode(true);
00228 p_dxl_serial->begin(baudrate);
00229 #endif
00230
00231 delay(100);
00232
00233 tx_time_per_byte = (1000.0 / (double)baudrate) * 10.0;
00234 return true;
00235 }
00236
00237 int PortHandlerArduino::checkBaudrateAvailable(int baudrate)
00238 {
00239 switch(baudrate)
00240 {
00241 case 9600:
00242 return 9600;
00243 case 57600:
00244 return 57600;
00245 case 115200:
00246 return 115200;
00247 case 1000000:
00248 return 1000000;
00249 case 2000000:
00250 return 2000000;
00251 case 3000000:
00252 return 3000000;
00253 case 4000000:
00254 return 4000000;
00255 case 4500000:
00256 return 4500000;
00257 default:
00258 return -1;
00259 }
00260 }
00261
00262 void PortHandlerArduino::setPowerOn()
00263 {
00264 #if defined(__OPENCR__)
00265 digitalWrite(BDPIN_DXL_PWR_EN, HIGH);
00266 #endif
00267 }
00268
00269 void PortHandlerArduino::setPowerOff()
00270 {
00271 #if defined(__OPENCR__)
00272 digitalWrite(BDPIN_DXL_PWR_EN, LOW);
00273 #endif
00274 }
00275
00276 void PortHandlerArduino::setTxEnable()
00277 {
00278 #if defined(__OPENCR__)
00279 drv_dxl_tx_enable(TRUE);
00280 #elif defined(__OPENCM904__)
00281 drv_dxl_tx_enable(socket_fd_, TRUE);
00282 #endif
00283 }
00284
00285 void PortHandlerArduino::setTxDisable()
00286 {
00287 #if defined(__OPENCR__)
00288 drv_dxl_tx_enable(FALSE);
00289 #elif defined(__OPENCM904__)
00290 drv_dxl_tx_enable(socket_fd_, FALSE);
00291 #endif
00292 }
00293
00294 #endif