-
Notifications
You must be signed in to change notification settings - Fork 63
Expand file tree
/
Copy pathport_handler.cpp
More file actions
192 lines (155 loc) · 3.59 KB
/
port_handler.cpp
File metadata and controls
192 lines (155 loc) · 3.59 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
#include "port_handler.h"
DXLPortHandler::DXLPortHandler()
: open_state_(false)
{}
/* DXLPortHandler */
bool DXLPortHandler::getOpenState()
{
return open_state_;
}
void DXLPortHandler::setOpenState(bool state)
{
open_state_ = state;
}
using namespace DYNAMIXEL;
/* SerialPortHandler */
SerialPortHandler::SerialPortHandler(HardwareSerial& port, const int dir_pin)
: DXLPortHandler(), port_(port), dir_pin_(dir_pin), baud_(57600)
{}
void SerialPortHandler::begin()
{
begin(baud_);
}
void SerialPortHandler::begin(unsigned long baud)
{
#if defined(ARDUINO_OpenCM904)
if(port_ == Serial1 && getOpenState() == false){
Serial1.setDxlMode(true);
}
#elif defined(ARDUINO_OpenRB)
if(port_ == Serial1 && getOpenState() == false){
pinMode(BDPIN_DXL_PWR_EN, OUTPUT);
digitalWrite(BDPIN_DXL_PWR_EN, HIGH);
delay(500); // Wait for the FET to turn on.
}
#elif defined(ARDUINO_OpenCR)
if(port_ == Serial3 && getOpenState() == false){
pinMode(BDPIN_DXL_PWR_EN, OUTPUT);
digitalWrite(BDPIN_DXL_PWR_EN, HIGH);
}
delay(500); // Wait for the DYNAMIXEL to power up normally.
#endif
baud_ = baud;
port_.begin(baud_);
mbedTXdelayus = 24000000 / baud;
if(dir_pin_ != -1){
pinMode(dir_pin_, OUTPUT);
digitalWrite(dir_pin_, LOW);
while(digitalRead(dir_pin_) != LOW);
}
#ifdef ARDUINO_ARCH_STM32
else{
port_.enableHalfDuplexRx();
}
#endif // ARDUINO_ARCH_STM32
setOpenState(true);
}
void SerialPortHandler::end(void)
{
#if defined(ARDUINO_OpenCR)
if(port_ == Serial3 && getOpenState() == true){
digitalWrite(BDPIN_DXL_PWR_EN, LOW);
}
#endif
port_.end();
setOpenState(false);
}
int SerialPortHandler::available(void)
{
return port_.available();
}
int SerialPortHandler::read()
{
return port_.read();
}
size_t SerialPortHandler::write(uint8_t c)
{
size_t ret = 0;
if(dir_pin_ != -1){
digitalWrite(dir_pin_, HIGH);
while(digitalRead(dir_pin_) != HIGH);
}
ret = port_.write(c);
if(dir_pin_ != -1){
port_.flush();
digitalWrite(dir_pin_, LOW);
while(digitalRead(dir_pin_) != LOW);
}
#ifdef ARDUINO_ARCH_STM32
else{
port_.enableHalfDuplexRx();
}
#endif // ARDUINO_ARCH_STM32
return ret;
}
size_t SerialPortHandler::write(uint8_t *buf, size_t len)
{
size_t ret;
if(dir_pin_ != -1){
digitalWrite(dir_pin_, HIGH);
while(digitalRead(dir_pin_) != HIGH);
}
ret = port_.write(buf, len);
if(dir_pin_ != -1){
port_.flush();
#if defined(ARDUINO_ARCH_MBED)
delayMicroseconds(mbedTXdelayus);
#endif
digitalWrite(dir_pin_, LOW);
while(digitalRead(dir_pin_) != LOW);
}
#ifdef ARDUINO_ARCH_STM32
else{
port_.enableHalfDuplexRx();
}
#endif // ARDUINO_ARCH_STM32
return ret;
}
unsigned long SerialPortHandler::getBaud() const
{
return baud_;
}
/* USBSerialPortHandler */
USBSerialPortHandler::USBSerialPortHandler(USB_SERIAL_CLASS& port)
: DXLPortHandler(), port_(port)
{}
void USBSerialPortHandler::begin()
{
port_.begin(1000000);
setOpenState(true);
}
void USBSerialPortHandler::end(void)
{
port_.end();
setOpenState(false);
}
int USBSerialPortHandler::available(void)
{
return port_.available();
}
int USBSerialPortHandler::read()
{
return port_.read();
}
size_t USBSerialPortHandler::write(uint8_t c)
{
size_t ret = 0;
ret = port_.write(c);
return ret;
}
size_t USBSerialPortHandler::write(uint8_t *buf, size_t len)
{
size_t ret;
ret = port_.write(buf, len);
return ret;
}