Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Issue #115 - allow override of hard-coded delay #116

Closed
wants to merge 2 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions src/Dynamixel2Arduino.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,7 @@ Dynamixel2Arduino::Dynamixel2Arduino(HardwareSerial& port, int dir_pin, uint16_t
}

/* For Master configuration */
void Dynamixel2Arduino::begin(unsigned long baud)
void Dynamixel2Arduino::begin(unsigned long baud, uint32_t delay)
{
p_dxl_port_ = (SerialPortHandler*)getPort();

Expand All @@ -137,7 +137,7 @@ void Dynamixel2Arduino::begin(unsigned long baud)
return;
}

p_dxl_port_->begin(baud);
p_dxl_port_->begin(baud, delay);
}

unsigned long Dynamixel2Arduino::getPortBaud()
Expand Down
3 changes: 2 additions & 1 deletion src/Dynamixel2Arduino.h
Original file line number Diff line number Diff line change
Expand Up @@ -80,9 +80,10 @@ class Dynamixel2Arduino : public DYNAMIXEL::Master
* dxl.begin(57600);
* @endcode
* @param baud The port speed you want on the board (the speed to communicate with DYNAMIXEL) (default : 57600)
* @param delay Delay in milliseconds after opening to allow hardware to settle (default: 300)
* @return It returns true(1) on success, false(0) on failure.
*/
void begin(unsigned long baud = 57600);
void begin(unsigned long baud = 57600, uint32_t delay = 300);

/**
* @brief It is API for getting serial baudrate of board port.
Expand Down
8 changes: 5 additions & 3 deletions src/utility/port_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ void SerialPortHandler::begin()
begin(baud_);
}

void SerialPortHandler::begin(unsigned long baud)
void SerialPortHandler::begin(unsigned long baud, uint32_t delay)
{
#if defined(ARDUINO_OpenCM904)
if(port_ == Serial1 && getOpenState() == false){
Expand All @@ -39,14 +39,16 @@ void SerialPortHandler::begin(unsigned long baud)
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.
if (delay)
delay(delay); // 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.
if (delay)
delay(delay); // Wait for the DYNAMIXEL to power up normally.
#endif

baud_ = baud;
Expand Down
4 changes: 2 additions & 2 deletions src/utility/port_handler.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ class SerialPortHandler : public DXLPortHandler
virtual size_t write(uint8_t) override;
virtual size_t write(uint8_t *buf, size_t len) override;

virtual void begin(unsigned long baud);
virtual void begin(unsigned long baud, uint32_t delay=300);
virtual unsigned long getBaud() const;

private:
Expand Down Expand Up @@ -101,4 +101,4 @@ class USBSerialPortHandler : public DXLPortHandler

}//namespace DYNAMIXEL

#endif /* DYNAMIXEL_PORT_HANDLER_HPP_ */
#endif /* DYNAMIXEL_PORT_HANDLER_HPP_ */