Skip to content

Commit fc039b0

Browse files
Merge pull request ROBOTIS-GIT#370 from ROBOTIS-GIT/develop
Fix two potential memory leaks. (ROBOTIS-GIT#361)
2 parents 7920e24 + cc5dd7b commit fc039b0

File tree

4 files changed

+60
-0
lines changed

4 files changed

+60
-0
lines changed

c++/src/dynamixel_sdk/protocol1_packet_handler.cpp

Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -412,6 +412,9 @@ int Protocol1PacketHandler::readRx(PortHandler *port, uint8_t id, uint16_t lengt
412412
uint8_t *rxpacket = (uint8_t *)malloc(RXPACKET_MAX_LEN); //(length+6);
413413
//uint8_t *rxpacket = new uint8_t[length+6];
414414

415+
if (rxpacket == NULL)
416+
return result;
417+
415418
do {
416419
result = rxPacket(port, rxpacket);
417420
} while (result == COMM_SUCCESS && rxpacket[PKT_ID] != id);
@@ -441,8 +444,14 @@ int Protocol1PacketHandler::readTxRx(PortHandler *port, uint8_t id, uint16_t add
441444
uint8_t txpacket[8] = {0};
442445
uint8_t *rxpacket = (uint8_t *)malloc(RXPACKET_MAX_LEN);//(length+6);
443446

447+
if (rxpacket == NULL)
448+
return result;
449+
444450
if (id >= BROADCAST_ID)
451+
{
452+
free(rxpacket);
445453
return COMM_NOT_AVAILABLE;
454+
}
446455

447456
txpacket[PKT_ID] = id;
448457
txpacket[PKT_LENGTH] = 4;
@@ -539,6 +548,9 @@ int Protocol1PacketHandler::writeTxOnly(PortHandler *port, uint8_t id, uint16_t
539548
uint8_t *txpacket = (uint8_t *)malloc(length+7);
540549
//uint8_t *txpacket = new uint8_t[length+7];
541550

551+
if (txpacket == NULL)
552+
return result;
553+
542554
txpacket[PKT_ID] = id;
543555
txpacket[PKT_LENGTH] = length+3;
544556
txpacket[PKT_INSTRUCTION] = INST_WRITE;
@@ -564,6 +576,9 @@ int Protocol1PacketHandler::writeTxRx(PortHandler *port, uint8_t id, uint16_t ad
564576
//uint8_t *txpacket = new uint8_t[length+7];
565577
uint8_t rxpacket[6] = {0};
566578

579+
if (txpacket == NULL)
580+
return result;
581+
567582
txpacket[PKT_ID] = id;
568583
txpacket[PKT_LENGTH] = length+3;
569584
txpacket[PKT_INSTRUCTION] = INST_WRITE;
@@ -620,6 +635,9 @@ int Protocol1PacketHandler::regWriteTxOnly(PortHandler *port, uint8_t id, uint16
620635
uint8_t *txpacket = (uint8_t *)malloc(length+6);
621636
//uint8_t *txpacket = new uint8_t[length+6];
622637

638+
if (txpacket == NULL)
639+
return result;
640+
623641
txpacket[PKT_ID] = id;
624642
txpacket[PKT_LENGTH] = length+3;
625643
txpacket[PKT_INSTRUCTION] = INST_REG_WRITE;
@@ -645,6 +663,9 @@ int Protocol1PacketHandler::regWriteTxRx(PortHandler *port, uint8_t id, uint16_t
645663
//uint8_t *txpacket = new uint8_t[length+6];
646664
uint8_t rxpacket[6] = {0};
647665

666+
if (txpacket == NULL)
667+
return result;
668+
648669
txpacket[PKT_ID] = id;
649670
txpacket[PKT_LENGTH] = length+3;
650671
txpacket[PKT_INSTRUCTION] = INST_REG_WRITE;
@@ -674,6 +695,9 @@ int Protocol1PacketHandler::syncWriteTxOnly(PortHandler *port, uint16_t start_ad
674695
// 8: HEADER0 HEADER1 ID LEN INST START_ADDR DATA_LEN ... CHKSUM
675696
//uint8_t *txpacket = new uint8_t[param_length + 8];
676697

698+
if (txpacket == NULL)
699+
return result;
700+
677701
txpacket[PKT_ID] = BROADCAST_ID;
678702
txpacket[PKT_LENGTH] = param_length + 4; // 4: INST START_ADDR DATA_LEN ... CHKSUM
679703
txpacket[PKT_INSTRUCTION] = INST_SYNC_WRITE;
@@ -699,6 +723,9 @@ int Protocol1PacketHandler::bulkReadTx(PortHandler *port, uint8_t *param, uint16
699723
// 7: HEADER0 HEADER1 ID LEN INST 0x00 ... CHKSUM
700724
//uint8_t *txpacket = new uint8_t[param_length + 7];
701725

726+
if (txpacket == NULL)
727+
return result;
728+
702729
txpacket[PKT_ID] = BROADCAST_ID;
703730
txpacket[PKT_LENGTH] = param_length + 3; // 3: INST 0x00 ... CHKSUM
704731
txpacket[PKT_INSTRUCTION] = INST_BULK_READ;

c++/src/dynamixel_sdk/protocol2_packet_handler.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -716,7 +716,10 @@ int Protocol2PacketHandler::readTxRx(PortHandler *port, uint8_t id, uint16_t add
716716
return result;
717717

718718
if (id >= BROADCAST_ID)
719+
{
720+
free(rxpacket);
719721
return COMM_NOT_AVAILABLE;
722+
}
720723

721724
txpacket[PKT_ID] = id;
722725
txpacket[PKT_LENGTH_L] = 7;

ros/src/dynamixel_sdk/protocol1_packet_handler.cpp

Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -412,6 +412,9 @@ int Protocol1PacketHandler::readRx(PortHandler *port, uint8_t id, uint16_t lengt
412412
uint8_t *rxpacket = (uint8_t *)malloc(RXPACKET_MAX_LEN); //(length+6);
413413
//uint8_t *rxpacket = new uint8_t[length+6];
414414

415+
if (rxpacket == NULL)
416+
return result;
417+
415418
do {
416419
result = rxPacket(port, rxpacket);
417420
} while (result == COMM_SUCCESS && rxpacket[PKT_ID] != id);
@@ -441,8 +444,14 @@ int Protocol1PacketHandler::readTxRx(PortHandler *port, uint8_t id, uint16_t add
441444
uint8_t txpacket[8] = {0};
442445
uint8_t *rxpacket = (uint8_t *)malloc(RXPACKET_MAX_LEN);//(length+6);
443446

447+
if (rxpacket == NULL)
448+
return result;
449+
444450
if (id >= BROADCAST_ID)
451+
{
452+
free(rxpacket);
445453
return COMM_NOT_AVAILABLE;
454+
}
446455

447456
txpacket[PKT_ID] = id;
448457
txpacket[PKT_LENGTH] = 4;
@@ -539,6 +548,9 @@ int Protocol1PacketHandler::writeTxOnly(PortHandler *port, uint8_t id, uint16_t
539548
uint8_t *txpacket = (uint8_t *)malloc(length+7);
540549
//uint8_t *txpacket = new uint8_t[length+7];
541550

551+
if (txpacket == NULL)
552+
return result;
553+
542554
txpacket[PKT_ID] = id;
543555
txpacket[PKT_LENGTH] = length+3;
544556
txpacket[PKT_INSTRUCTION] = INST_WRITE;
@@ -564,6 +576,9 @@ int Protocol1PacketHandler::writeTxRx(PortHandler *port, uint8_t id, uint16_t ad
564576
//uint8_t *txpacket = new uint8_t[length+7];
565577
uint8_t rxpacket[6] = {0};
566578

579+
if (txpacket == NULL)
580+
return result;
581+
567582
txpacket[PKT_ID] = id;
568583
txpacket[PKT_LENGTH] = length+3;
569584
txpacket[PKT_INSTRUCTION] = INST_WRITE;
@@ -620,6 +635,9 @@ int Protocol1PacketHandler::regWriteTxOnly(PortHandler *port, uint8_t id, uint16
620635
uint8_t *txpacket = (uint8_t *)malloc(length+6);
621636
//uint8_t *txpacket = new uint8_t[length+6];
622637

638+
if (txpacket == NULL)
639+
return result;
640+
623641
txpacket[PKT_ID] = id;
624642
txpacket[PKT_LENGTH] = length+3;
625643
txpacket[PKT_INSTRUCTION] = INST_REG_WRITE;
@@ -645,6 +663,9 @@ int Protocol1PacketHandler::regWriteTxRx(PortHandler *port, uint8_t id, uint16_t
645663
//uint8_t *txpacket = new uint8_t[length+6];
646664
uint8_t rxpacket[6] = {0};
647665

666+
if (txpacket == NULL)
667+
return result;
668+
648669
txpacket[PKT_ID] = id;
649670
txpacket[PKT_LENGTH] = length+3;
650671
txpacket[PKT_INSTRUCTION] = INST_REG_WRITE;
@@ -674,6 +695,9 @@ int Protocol1PacketHandler::syncWriteTxOnly(PortHandler *port, uint16_t start_ad
674695
// 8: HEADER0 HEADER1 ID LEN INST START_ADDR DATA_LEN ... CHKSUM
675696
//uint8_t *txpacket = new uint8_t[param_length + 8];
676697

698+
if (txpacket == NULL)
699+
return result;
700+
677701
txpacket[PKT_ID] = BROADCAST_ID;
678702
txpacket[PKT_LENGTH] = param_length + 4; // 4: INST START_ADDR DATA_LEN ... CHKSUM
679703
txpacket[PKT_INSTRUCTION] = INST_SYNC_WRITE;
@@ -699,6 +723,9 @@ int Protocol1PacketHandler::bulkReadTx(PortHandler *port, uint8_t *param, uint16
699723
// 7: HEADER0 HEADER1 ID LEN INST 0x00 ... CHKSUM
700724
//uint8_t *txpacket = new uint8_t[param_length + 7];
701725

726+
if (txpacket == NULL)
727+
return result;
728+
702729
txpacket[PKT_ID] = BROADCAST_ID;
703730
txpacket[PKT_LENGTH] = param_length + 3; // 3: INST 0x00 ... CHKSUM
704731
txpacket[PKT_INSTRUCTION] = INST_BULK_READ;

ros/src/dynamixel_sdk/protocol2_packet_handler.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -716,7 +716,10 @@ int Protocol2PacketHandler::readTxRx(PortHandler *port, uint8_t id, uint16_t add
716716
return result;
717717

718718
if (id >= BROADCAST_ID)
719+
{
720+
free(rxpacket);
719721
return COMM_NOT_AVAILABLE;
722+
}
720723

721724
txpacket[PKT_ID] = id;
722725
txpacket[PKT_LENGTH_L] = 7;

0 commit comments

Comments
 (0)