@@ -840,6 +840,10 @@ std::string Dynamixel::DxlErrorToString(DxlError error_num)
840840
841841DxlError Dynamixel::ReadMultiDxlData (double period_ms)
842842{
843+ if (read_data_list_.empty ()) {
844+ return DxlError::OK;
845+ }
846+
843847 if (read_type_ == SYNC) {
844848 return GetDxlValueFromSyncRead (period_ms);
845849 } else {
@@ -849,6 +853,10 @@ DxlError Dynamixel::ReadMultiDxlData(double period_ms)
849853
850854DxlError Dynamixel::WriteMultiDxlData ()
851855{
856+ if (write_data_list_.empty ()) {
857+ return DxlError::OK;
858+ }
859+
852860 if (write_type_ == SYNC) {
853861 return SetDxlValueToSyncWrite ();
854862 } else {
@@ -1790,10 +1798,6 @@ DxlError Dynamixel::SetSyncWriteHandler(std::vector<uint8_t> id_arr)
17901798}
17911799DxlError Dynamixel::SetDxlValueToSyncWrite ()
17921800{
1793- if (write_data_list_.size () == 0 ) {
1794- return DxlError::OK;
1795- }
1796-
17971801 for (auto it_write_data : write_data_list_) {
17981802 uint8_t comm_id = it_write_data.comm_id ;
17991803 uint8_t * param_write_value = new uint8_t [indirect_info_write_[comm_id].size ];
@@ -1977,10 +1981,6 @@ DxlError Dynamixel::SetBulkWriteHandler(std::vector<uint8_t> id_arr)
19771981
19781982DxlError Dynamixel::SetDxlValueToBulkWrite ()
19791983{
1980- if (write_data_list_.size () == 0 ) {
1981- return DxlError::OK;
1982- }
1983-
19841984 for (auto it_write_data : write_data_list_) {
19851985 uint8_t comm_id = it_write_data.comm_id ;
19861986 uint8_t * param_write_value;
0 commit comments