We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent 8b56667 commit b745e7fCopy full SHA for b745e7f
examples/basic/position_mode/position_mode.ino
@@ -93,7 +93,7 @@ void loop() {
93
int i_present_position = 0;
94
float f_present_position = 0.0;
95
96
- while (abs(512 - i_present_position) > 10)
+ while (abs(4000 - i_present_position) > 10)
97
{
98
f_present_position = dxl.getPresentPosition(DXL_ID, UNIT_DEGREE);
99
i_present_position = dxl.getPresentPosition(DXL_ID);
src/utility/port_handler.cpp
@@ -39,6 +39,7 @@ void SerialPortHandler::begin(unsigned long baud)
39
if(port_ == Serial1 && getOpenState() == false){
40
pinMode(BDPIN_DXL_PWR_EN, OUTPUT);
41
digitalWrite(BDPIN_DXL_PWR_EN, HIGH);
42
+ delay(300); // Wait for the FET to turn on.
43
}
44
#elif defined(ARDUINO_OpenCR)
45
if(port_ == Serial3 && getOpenState() == false){
0 commit comments