Skip to content

Commit e125298

Browse files
authored
Merge pull request ROBOTIS-GIT#630 from honghyun79/master
Clear Error Implementation
2 parents 886225c + 272e7e7 commit e125298

File tree

9 files changed

+68
-5
lines changed

9 files changed

+68
-5
lines changed
512 Bytes
Binary file not shown.
988 Bytes
Binary file not shown.
0 Bytes
Binary file not shown.
1020 Bytes
Binary file not shown.

c++/include/dynamixel_sdk/packet_handler.h

Lines changed: 16 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -224,10 +224,11 @@ class WINDECLSPEC PacketHandler
224224
/// @description transmits the packet with PacketHandler::txRxPacket(),
225225
/// @description then Dynamixel reboots.
226226
/// @description During reboot, its LED will blink.
227+
/// @description It will take some time to reboot. It will take longer for Y series.
227228
/// @param port PortHandler instance
228229
/// @param id Dynamixel ID
229230
/// @param error Dynamixel hardware error
230-
/// @return COMM_NOT_AVAILABLE
231+
/// @return communication results which come from PacketHandler::txRxPacket()
231232
////////////////////////////////////////////////////////////////////////////////
232233
virtual int reboot (PortHandler *port, uint8_t id, uint8_t *error = 0) = 0;
233234

@@ -236,14 +237,27 @@ class WINDECLSPEC PacketHandler
236237
/// @description The function makes an instruction packet with INST_CLEAR,
237238
/// @description transmits the packet with PacketHandler::txRxPacket().
238239
/// @description Applied Products : MX with Protocol 2.0 (Firmware v42 or above),
239-
/// @description Dynamixel X-series (Firmware v42 or above).
240+
/// @description DYNAMIXEL X-series (Firmware v42 or above), DYNAMIXEL Y-series.
241+
/// @description It will take some time to clear. It will take longer for Y series.
240242
/// @param port PortHandler instance
241243
/// @param id Dynamixel ID
242244
/// @param error Dynamixel hardware error
243245
/// @return communication results which come from PacketHandler::txRxPacket()
244246
////////////////////////////////////////////////////////////////////////////////
245247
virtual int clearMultiTurn (PortHandler *port, uint8_t id, uint8_t *error = 0) = 0;
246248

249+
////////////////////////////////////////////////////////////////////////////////
250+
/// @brief The function that clear errors that occurred in DYNAMIXEL
251+
/// @description The function makes an instruction packet with INST_CLEAR,
252+
/// @description transmits the packet with PacketHandler::txRxPacket().
253+
/// @description Applied Products : DYNAMIXEL Y-series.
254+
/// @param port PortHandler instance
255+
/// @param id DYNAMIXEL ID
256+
/// @param error DYNAMIXEL hardware error
257+
/// @return communication results which come from PacketHandler::txRxPacket()
258+
////////////////////////////////////////////////////////////////////////////////
259+
virtual int clearError (PortHandler *port, uint8_t id, uint8_t *error = 0) = 0;
260+
247261
////////////////////////////////////////////////////////////////////////////////
248262
/// @brief The function that makes Dynamixel reset as it was produced in the factory
249263
/// @description The function makes an instruction packet with INST_FACTORY_RESET,

c++/include/dynamixel_sdk/protocol1_packet_handler.h

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -187,6 +187,15 @@ class WINDECLSPEC Protocol1PacketHandler : public PacketHandler
187187
////////////////////////////////////////////////////////////////////////////////
188188
int clearMultiTurn (PortHandler *port, uint8_t id, uint8_t *error = 0);
189189

190+
////////////////////////////////////////////////////////////////////////////////
191+
/// @brief (Available only in Protocol 2.0) The function that clear errors that occurred in DYNAMIXEL
192+
/// @param port PortHandler instance
193+
/// @param id DYNAMIXEL ID
194+
/// @param error DYNAMIXEL hardware error
195+
/// @return COMM_NOT_AVAILABLE
196+
////////////////////////////////////////////////////////////////////////////////
197+
int clearError (PortHandler *port, uint8_t id, uint8_t *error = 0);
198+
190199
////////////////////////////////////////////////////////////////////////////////
191200
/// @brief The function that makes Dynamixel reset as it was produced in the factory
192201
/// @description The function makes an instruction packet with INST_FACTORY_RESET,

c++/include/dynamixel_sdk/protocol2_packet_handler.h

Lines changed: 16 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -179,26 +179,39 @@ class WINDECLSPEC Protocol2PacketHandler : public PacketHandler
179179
/// @description transmits the packet with Protocol2PacketHandler::txRxPacket(),
180180
/// @description then Dynamixel reboots.
181181
/// @description During reboot, its LED will blink.
182+
/// @description It will take some time to reboot. It will take longer for Y series.
182183
/// @param port PortHandler instance
183184
/// @param id Dynamixel ID
184185
/// @param error Dynamixel hardware error
185-
/// @return COMM_NOT_AVAILABLE
186+
/// @return communication results which come from PacketHandler::txRxPacket()
186187
////////////////////////////////////////////////////////////////////////////////
187188
int reboot (PortHandler *port, uint8_t id, uint8_t *error = 0);
188189

189190
////////////////////////////////////////////////////////////////////////////////
190191
/// @brief The function that reset multi-turn revolution information of Dynamixel
191192
/// @description The function makes an instruction packet with INST_CLEAR,
192193
/// @description transmits the packet with Protocol2PacketHandler::txRxPacket().
193-
/// @description Applied Products : MX with Protocol 2.0 (Firmware v42 or above),
194-
/// @description Dynamixel X-series (Firmware v42 or above).
194+
/// @description DYNAMIXEL X-series (Firmware v42 or above), DYNAMIXEL Y-series.
195+
/// @description It will take some time to clear. It will take longer for Y series.
195196
/// @param port PortHandler instance
196197
/// @param id Dynamixel ID
197198
/// @param error Dynamixel hardware error
198199
/// @return communication results which come from Protocol2PacketHandler::txRxPacket()
199200
////////////////////////////////////////////////////////////////////////////////
200201
int clearMultiTurn (PortHandler *port, uint8_t id, uint8_t *error = 0);
201202

203+
////////////////////////////////////////////////////////////////////////////////
204+
/// @brief The function that clear errors that occurred in DYNAMIXEL
205+
/// @description The function makes an instruction packet with INST_CLEAR,
206+
/// @description transmits the packet with PacketHandler::txRxPacket().
207+
/// @description Applied Products : DYNAMIXEL Y-series.
208+
/// @param port PortHandler instance
209+
/// @param id DYNAMIXEL ID
210+
/// @param error DYNAMIXEL hardware error
211+
/// @return communication results which come from PacketHandler::txRxPacket()
212+
////////////////////////////////////////////////////////////////////////////////
213+
int clearError (PortHandler *port, uint8_t id, uint8_t *error = 0);
214+
202215
////////////////////////////////////////////////////////////////////////////////
203216
/// @brief The function that makes Dynamixel reset as it was produced in the factory
204217
/// @description The function makes an instruction packet with INST_FACTORY_RESET,

c++/src/dynamixel_sdk/protocol1_packet_handler.cpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -370,6 +370,11 @@ int Protocol1PacketHandler::clearMultiTurn(PortHandler *port, uint8_t id, uint8_
370370
return COMM_NOT_AVAILABLE;
371371
}
372372

373+
int Protocol1PacketHandler::clearError(PortHandler *port, uint8_t id, uint8_t *error)
374+
{
375+
return COMM_NOT_AVAILABLE;
376+
}
377+
373378
int Protocol1PacketHandler::factoryReset(PortHandler *port, uint8_t id, uint8_t option, uint8_t *error)
374379
{
375380
uint8_t txpacket[6] = {0};

c++/src/dynamixel_sdk/protocol2_packet_handler.cpp

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -446,6 +446,10 @@ int Protocol2PacketHandler::txRxPacket(PortHandler *port, uint8_t *txpacket, uin
446446
{
447447
port->setPacketTimeout((uint16_t)(DXL_MAKEWORD(txpacket[PKT_PARAMETER0+2], txpacket[PKT_PARAMETER0+3]) + 11));
448448
}
449+
else if (txpacket[PKT_INSTRUCTION] == INST_CLEAR)
450+
{
451+
port->setPacketTimeout((double)10000);
452+
}
449453
else
450454
{
451455
port->setPacketTimeout((uint16_t)11);
@@ -633,6 +637,24 @@ int Protocol2PacketHandler::clearMultiTurn(PortHandler *port, uint8_t id, uint8_
633637
return txRxPacket(port, txpacket, rxpacket, error);
634638
}
635639

640+
int Protocol2PacketHandler::clearError(PortHandler *port, uint8_t id, uint8_t *error)
641+
{
642+
uint8_t txpacket[15] = {0};
643+
uint8_t rxpacket[11] = {0};
644+
645+
txpacket[PKT_ID] = id;
646+
txpacket[PKT_LENGTH_L] = 8;
647+
txpacket[PKT_LENGTH_H] = 0;
648+
txpacket[PKT_INSTRUCTION] = INST_CLEAR;
649+
txpacket[PKT_PARAMETER0] = 0x02;
650+
txpacket[PKT_PARAMETER0+1] = 0x45;
651+
txpacket[PKT_PARAMETER0+2] = 0x52;
652+
txpacket[PKT_PARAMETER0+3] = 0x43;
653+
txpacket[PKT_PARAMETER0+4] = 0x4C;
654+
655+
return txRxPacket(port, txpacket, rxpacket, error);
656+
}
657+
636658
int Protocol2PacketHandler::factoryReset(PortHandler *port, uint8_t id, uint8_t option, uint8_t *error)
637659
{
638660
uint8_t txpacket[11] = {0};

0 commit comments

Comments
 (0)