Skip to content

Commit b745e7f

Browse files
committed
add delay for FET
Signed-off-by: ROBOTIS-Will <[email protected]>
1 parent 8b56667 commit b745e7f

File tree

2 files changed

+2
-1
lines changed

2 files changed

+2
-1
lines changed

examples/basic/position_mode/position_mode.ino

+1-1
Original file line numberDiff line numberDiff line change
@@ -93,7 +93,7 @@ void loop() {
9393
int i_present_position = 0;
9494
float f_present_position = 0.0;
9595

96-
while (abs(512 - i_present_position) > 10)
96+
while (abs(4000 - i_present_position) > 10)
9797
{
9898
f_present_position = dxl.getPresentPosition(DXL_ID, UNIT_DEGREE);
9999
i_present_position = dxl.getPresentPosition(DXL_ID);

src/utility/port_handler.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@ void SerialPortHandler::begin(unsigned long baud)
3939
if(port_ == Serial1 && getOpenState() == false){
4040
pinMode(BDPIN_DXL_PWR_EN, OUTPUT);
4141
digitalWrite(BDPIN_DXL_PWR_EN, HIGH);
42+
delay(300); // Wait for the FET to turn on.
4243
}
4344
#elif defined(ARDUINO_OpenCR)
4445
if(port_ == Serial3 && getOpenState() == false){

0 commit comments

Comments
 (0)