From d830ef1df0cffd0ec2f24d464dde0a46aa15c184 Mon Sep 17 00:00:00 2001 From: ROBOTIS <platform@robotis.com> Date: Fri, 11 Mar 2016 15:11:10 +0900 Subject: [PATCH] - if the last bulk_read / sync_read result is failure -> GetData return false --- c++/include/dynamixel_sdk/GroupBulkRead.h | 8 +++++--- c++/include/dynamixel_sdk/GroupSyncRead.h | 2 ++ c++/src/dynamixel_sdk/GroupBulkRead.cpp | 12 +++++++++--- c++/src/dynamixel_sdk/GroupSyncRead.cpp | 12 +++++++++--- 4 files changed, 25 insertions(+), 9 deletions(-) diff --git a/c++/include/dynamixel_sdk/GroupBulkRead.h b/c++/include/dynamixel_sdk/GroupBulkRead.h index e98b19f1..45706c95 100644 --- a/c++/include/dynamixel_sdk/GroupBulkRead.h +++ b/c++/include/dynamixel_sdk/GroupBulkRead.h @@ -21,15 +21,17 @@ namespace ROBOTIS class GroupBulkRead { private: - PortHandler *port_; - PacketHandler *ph_; + PortHandler *port_; + PacketHandler *ph_; std::vector<UINT8_T> id_list_; std::map<UINT8_T, UINT16_T> address_list_; // <id, start_address> std::map<UINT8_T, UINT16_T> length_list_; // <id, data_length> std::map<UINT8_T, UINT8_T *> data_list_; // <id, data> - UINT8_T *param_; + bool last_result_; + + UINT8_T *param_; void MakeParam(); diff --git a/c++/include/dynamixel_sdk/GroupSyncRead.h b/c++/include/dynamixel_sdk/GroupSyncRead.h index 5fb7b5e7..56f7cffe 100644 --- a/c++/include/dynamixel_sdk/GroupSyncRead.h +++ b/c++/include/dynamixel_sdk/GroupSyncRead.h @@ -27,6 +27,8 @@ private: std::vector<UINT8_T> id_list_; std::map<UINT8_T, UINT8_T* > data_list_; // <id, data> + bool last_result_; + UINT8_T *param_; UINT16_T start_address_; UINT16_T data_length_; diff --git a/c++/src/dynamixel_sdk/GroupBulkRead.cpp b/c++/src/dynamixel_sdk/GroupBulkRead.cpp index d779039a..aa085870 100644 --- a/c++/src/dynamixel_sdk/GroupBulkRead.cpp +++ b/c++/src/dynamixel_sdk/GroupBulkRead.cpp @@ -14,6 +14,7 @@ using namespace ROBOTIS; GroupBulkRead::GroupBulkRead(PortHandler *port, PacketHandler *ph) : port_(port), ph_(ph), + last_result_(false), param_(0) { ClearParam(); @@ -116,6 +117,8 @@ int GroupBulkRead::RxPacket() int _cnt = id_list_.size(); int _result = COMM_RX_FAIL; + last_result_ = false; + if(_cnt == 0) return COMM_NOT_AVAILABLE; @@ -131,6 +134,9 @@ int GroupBulkRead::RxPacket() } } + if(_result == COMM_SUCCESS) + last_result_ = true; + return _result; } @@ -149,7 +155,7 @@ bool GroupBulkRead::GetData(UINT8_T id, UINT16_T address, UINT8_T *data) { UINT16_T _start_addr, _data_length; - if(data_list_.find(id) == data_list_.end()) + if(last_result_ == false || data_list_.find(id) == data_list_.end()) return false; _start_addr = address_list_[id]; @@ -167,7 +173,7 @@ bool GroupBulkRead::GetData(UINT8_T id, UINT16_T address, UINT16_T *data) { UINT16_T _start_addr, _data_length; - if(data_list_.find(id) == data_list_.end()) + if(last_result_ == false || data_list_.find(id) == data_list_.end()) return false; _start_addr = address_list_[id]; @@ -185,7 +191,7 @@ bool GroupBulkRead::GetData(UINT8_T id, UINT16_T address, UINT32_T *data) { UINT16_T _start_addr, _data_length; - if(data_list_.find(id) == data_list_.end()) + if(last_result_ == false || data_list_.find(id) == data_list_.end()) return false; _start_addr = address_list_[id]; diff --git a/c++/src/dynamixel_sdk/GroupSyncRead.cpp b/c++/src/dynamixel_sdk/GroupSyncRead.cpp index 7f123934..cf399e08 100644 --- a/c++/src/dynamixel_sdk/GroupSyncRead.cpp +++ b/c++/src/dynamixel_sdk/GroupSyncRead.cpp @@ -13,6 +13,7 @@ using namespace ROBOTIS; GroupSyncRead::GroupSyncRead(PortHandler *port, PacketHandler *ph, UINT16_T start_address, UINT16_T data_length) : port_(port), ph_(ph), + last_result_(false), param_(0), start_address_(start_address), data_length_(data_length) @@ -93,6 +94,8 @@ int GroupSyncRead::TxPacket() int GroupSyncRead::RxPacket() { + last_result_ = false; + if(ph_->GetProtocolVersion() == 1.0) return COMM_NOT_AVAILABLE; @@ -111,6 +114,9 @@ int GroupSyncRead::RxPacket() return _result; } + if(_result == COMM_SUCCESS) + last_result_ = true; + return _result; } @@ -130,7 +136,7 @@ int GroupSyncRead::TxRxPacket() bool GroupSyncRead::GetData(UINT8_T id, UINT16_T address, UINT8_T *data) { - if(ph_->GetProtocolVersion() == 1.0) + if(last_result_ == false || ph_->GetProtocolVersion() == 1.0) return false; if(data_list_.find(id) == data_list_.end()) @@ -145,7 +151,7 @@ bool GroupSyncRead::GetData(UINT8_T id, UINT16_T address, UINT8_T *data) } bool GroupSyncRead::GetData(UINT8_T id, UINT16_T address, UINT16_T *data) { - if(ph_->GetProtocolVersion() == 1.0) + if(last_result_ == false || ph_->GetProtocolVersion() == 1.0) return false; if(data_list_.find(id) == data_list_.end()) @@ -160,7 +166,7 @@ bool GroupSyncRead::GetData(UINT8_T id, UINT16_T address, UINT16_T *data) } bool GroupSyncRead::GetData(UINT8_T id, UINT16_T address, UINT32_T *data) { - if(ph_->GetProtocolVersion() == 1.0) + if(last_result_ == false || ph_->GetProtocolVersion() == 1.0) return false; if(data_list_.find(id) == data_list_.end()) -- GitLab