- if the last bulk_read / sync_read result is failure -> GetData return false
This commit is contained in:
		| @@ -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(); | ||||
|  | ||||
|   | ||||
| @@ -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_; | ||||
|   | ||||
| @@ -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]; | ||||
|   | ||||
| @@ -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()) | ||||
|   | ||||
		Reference in New Issue
	
	Block a user
	 ROBOTIS
					ROBOTIS