Skip to content

Commit 059b4b3

Browse files
committed
Fixed buffer overflow bug (rxpacket size)
Signed-off-by: Pyo <[email protected]>
1 parent 40ae153 commit 059b4b3

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

c++/src/dynamixel_sdk/protocol2_packet_handler.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -674,7 +674,7 @@ int Protocol2PacketHandler::readTx(PortHandler *port, uint8_t id, uint16_t addre
674674
int Protocol2PacketHandler::readRx(PortHandler *port, uint8_t id, uint16_t length, uint8_t *data, uint8_t *error)
675675
{
676676
int result = COMM_TX_FAIL;
677-
uint8_t *rxpacket = (uint8_t *)malloc(length + 11 + (length / 3));
677+
uint8_t *rxpacket = (uint8_t *)malloc(RXPACKET_MAX_LEN);
678678
//(length + 11 + (length/3)); // (length/3): consider stuffing
679679

680680
if (rxpacket == NULL)
@@ -706,7 +706,7 @@ int Protocol2PacketHandler::readTxRx(PortHandler *port, uint8_t id, uint16_t add
706706
int result = COMM_TX_FAIL;
707707

708708
uint8_t txpacket[14] = {0};
709-
uint8_t *rxpacket = (uint8_t *)malloc(length + 11 + (length / 3));
709+
uint8_t *rxpacket = (uint8_t *)malloc(RXPACKET_MAX_LEN);
710710
//(length + 11 + (length/3)); // (length/3): consider stuffing
711711

712712
if (rxpacket == NULL)

0 commit comments

Comments
 (0)