Skip to content
Snippets Groups Projects
Commit 347948f9 authored by ROBOTIS-zerom's avatar ROBOTIS-zerom
Browse files

- GetData() function changed.

parent 3ff7063d
No related branches found
No related tags found
No related merge requests found
......@@ -51,9 +51,7 @@ public:
int RxPacket();
int TxRxPacket();
bool GetData(UINT8_T id, UINT16_T address, UINT8_T *data);
bool GetData(UINT8_T id, UINT16_T address, UINT16_T *data);
bool GetData(UINT8_T id, UINT16_T address, UINT32_T *data);
bool GetData(UINT8_T id, UINT16_T address, UINT32_T *data, UINT16_T data_length);
};
}
......
......@@ -51,9 +51,7 @@ public:
int RxPacket();
int TxRxPacket();
bool GetData(UINT8_T id, UINT16_T address, UINT8_T *data);
bool GetData(UINT8_T id, UINT16_T address, UINT16_T *data);
bool GetData(UINT8_T id, UINT16_T address, UINT32_T *data);
bool GetData(UINT8_T id, UINT16_T address, UINT32_T *data, UINT16_T data_length);
};
}
......
......@@ -22,6 +22,7 @@ public:
static PortHandler *GetPortHandler(const char *port_name);
bool is_using;
float default_protocol;
virtual ~PortHandler() { }
......
......@@ -155,7 +155,7 @@ int GroupBulkRead::TxRxPacket()
return RxPacket();
}
bool GroupBulkRead::GetData(UINT8_T id, UINT16_T address, UINT8_T *data)
bool GroupBulkRead::GetData(UINT8_T id, UINT16_T address, UINT32_T *data, UINT16_T data_length)
{
UINT16_T _start_addr, _data_length;
......@@ -165,47 +165,24 @@ bool GroupBulkRead::GetData(UINT8_T id, UINT16_T address, UINT8_T *data)
_start_addr = address_list_[id];
_data_length = length_list_[id];
if(address < _start_addr || _start_addr + _data_length - 1 < address)
if(address < _start_addr || _start_addr + _data_length - data_length < address)
return false;
*data = data_list_[id][address - _start_addr];
return true;
}
bool GroupBulkRead::GetData(UINT8_T id, UINT16_T address, UINT16_T *data)
{
UINT16_T _start_addr, _data_length;
if(last_result_ == false || data_list_.find(id) == data_list_.end())
return false;
_start_addr = address_list_[id];
_data_length = length_list_[id];
if(address < _start_addr || _start_addr + _data_length - 2 < address)
return false;
*data = DXL_MAKEWORD(data_list_[id][address - _start_addr], data_list_[id][address - _start_addr + 1]);
return true;
}
bool GroupBulkRead::GetData(UINT8_T id, UINT16_T address, UINT32_T *data)
{
UINT16_T _start_addr, _data_length;
if(last_result_ == false || data_list_.find(id) == data_list_.end())
return false;
_start_addr = address_list_[id];
_data_length = length_list_[id];
if(address < _start_addr || _start_addr + _data_length - 4 < address)
switch(data_length)
{
case 1:
*data = data_list_[id][address - _start_addr];
break;
case 2:
*data = DXL_MAKEWORD(data_list_[id][address - _start_addr], data_list_[id][address - _start_addr + 1]);
break;
case 4:
*data = DXL_MAKEDWORD(DXL_MAKEWORD(data_list_[id][address - _start_addr + 0], data_list_[id][address - _start_addr + 1]),
DXL_MAKEWORD(data_list_[id][address - _start_addr + 2], data_list_[id][address - _start_addr + 3]));
break;
default:
return false;
*data = DXL_MAKEDWORD(DXL_MAKEWORD(data_list_[id][address - _start_addr + 0], data_list_[id][address - _start_addr + 1]),
DXL_MAKEWORD(data_list_[id][address - _start_addr + 2], data_list_[id][address - _start_addr + 3]));
}
return true;
}
......
......@@ -138,7 +138,7 @@ int GroupSyncRead::TxRxPacket()
return RxPacket();
}
bool GroupSyncRead::GetData(UINT8_T id, UINT16_T address, UINT8_T *data)
bool GroupSyncRead::GetData(UINT8_T id, UINT16_T address, UINT32_T *data, UINT16_T data_length)
{
if(last_result_ == false || ph_->GetProtocolVersion() == 1.0)
return false;
......@@ -146,41 +146,24 @@ bool GroupSyncRead::GetData(UINT8_T id, UINT16_T address, UINT8_T *data)
if(data_list_.find(id) == data_list_.end())
return false;
if(address < start_address_ || start_address_ + data_length_ - 1 < address)
if(address < start_address_ || start_address_ + data_length_ - data_length < address)
return false;
*data = data_list_[id][address - start_address_];
return true;
}
bool GroupSyncRead::GetData(UINT8_T id, UINT16_T address, UINT16_T *data)
{
if(last_result_ == false || ph_->GetProtocolVersion() == 1.0)
return false;
if(data_list_.find(id) == data_list_.end())
return false;
if(address < start_address_ || start_address_ + data_length_ - 2 < address)
return false;
*data = DXL_MAKEWORD(data_list_[id][address - start_address_], data_list_[id][address - start_address_ + 1]);
return true;
}
bool GroupSyncRead::GetData(UINT8_T id, UINT16_T address, UINT32_T *data)
{
if(last_result_ == false || ph_->GetProtocolVersion() == 1.0)
return false;
if(data_list_.find(id) == data_list_.end())
return false;
if(address < start_address_ || start_address_ + data_length_ - 4 < address)
switch(data_length)
{
case 1:
*data = data_list_[id][address - start_address_];
break;
case 2:
*data = DXL_MAKEWORD(data_list_[id][address - start_address_], data_list_[id][address - start_address_ + 1]);
break;
case 4:
*data = DXL_MAKEDWORD(DXL_MAKEWORD(data_list_[id][address - start_address_ + 0], data_list_[id][address - start_address_ + 1]),
DXL_MAKEWORD(data_list_[id][address - start_address_ + 2], data_list_[id][address - start_address_ + 3]));
break;
default:
return false;
*data = DXL_MAKEDWORD(DXL_MAKEWORD(data_list_[id][address - start_address_ + 0], data_list_[id][address - start_address_ + 1]),
DXL_MAKEWORD(data_list_[id][address - start_address_ + 2], data_list_[id][address - start_address_ + 3]));
}
return true;
}
......
......@@ -29,6 +29,7 @@ PortHandlerLinux::PortHandlerLinux(const char *port_name)
tx_time_per_byte(0.0)
{
is_using = false;
default_protocol = 2.0;
SetPortName(port_name);
}
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment