-
Notifications
You must be signed in to change notification settings - Fork 12
Bump 1.4.3 #34
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Bump 1.4.3 #34
Changes from all commits
b1d8a28
ebce0be
99e1702
32b08ab
85b2763
cdb4d70
541632c
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change | ||||||
|---|---|---|---|---|---|---|---|---|
|
|
@@ -635,6 +635,8 @@ std::string Dynamixel::DxlErrorToString(DxlError error_num) | |||||||
| return "DLX_HARDWARE_ERROR"; | ||||||||
| case DXL_REBOOT_FAIL: | ||||||||
| return "DXL_REBOOT_FAIL"; | ||||||||
| default: | ||||||||
| return "UNKNOWN_ERROR"; | ||||||||
| } | ||||||||
| } | ||||||||
|
|
||||||||
|
|
@@ -965,15 +967,15 @@ DxlError Dynamixel::ProcessReadCommunication( | |||||||
| dxl_comm_result = group_sync_read->txPacket(); | ||||||||
| if (dxl_comm_result != COMM_SUCCESS) { | ||||||||
| fprintf( | ||||||||
| stderr, "SyncRead Tx Fail [Dxl Size : %d] [Error code : %d]\n", | ||||||||
| stderr, "SyncRead Tx Fail [Dxl Size : %ld] [Error code : %d]\n", | ||||||||
| read_data_list_.size(), dxl_comm_result); | ||||||||
| return DxlError::SYNC_READ_FAIL; | ||||||||
| } | ||||||||
| } else { | ||||||||
| dxl_comm_result = group_bulk_read->txPacket(); | ||||||||
| if (dxl_comm_result != COMM_SUCCESS) { | ||||||||
| fprintf( | ||||||||
| stderr, "BulkRead Tx Fail [Dxl Size : %d] [Error code : %d]\n", | ||||||||
| stderr, "BulkRead Tx Fail [Dxl Size : %ld] [Error code : %d]\n", | ||||||||
|
Contributor
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Consider using
Suggested change
|
||||||||
| read_data_list_.size(), dxl_comm_result); | ||||||||
| return DxlError::BULK_READ_FAIL; | ||||||||
| } | ||||||||
|
|
@@ -989,15 +991,15 @@ DxlError Dynamixel::ProcessReadCommunication( | |||||||
| dxl_comm_result = group_sync_read->rxPacket(); | ||||||||
| if (dxl_comm_result != COMM_SUCCESS) { | ||||||||
| fprintf( | ||||||||
|
Contributor
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Consider using
Suggested change
|
||||||||
| stderr, "SyncRead Rx Fail [Dxl Size : %d] [Error code : %d]\n", | ||||||||
| stderr, "SyncRead Rx Fail [Dxl Size : %ld] [Error code : %d]\n", | ||||||||
| read_data_list_.size(), dxl_comm_result); | ||||||||
| return DxlError::SYNC_READ_FAIL; | ||||||||
| } | ||||||||
| } else { | ||||||||
| dxl_comm_result = group_bulk_read->rxPacket(); | ||||||||
| if (dxl_comm_result != COMM_SUCCESS) { | ||||||||
| fprintf( | ||||||||
| stderr, "BulkRead Rx Fail [Dxl Size : %d] [Error code : %d]\n", | ||||||||
| stderr, "BulkRead Rx Fail [Dxl Size : %ld] [Error code : %d]\n", | ||||||||
|
Contributor
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Consider using
Suggested change
|
||||||||
| read_data_list_.size(), dxl_comm_result); | ||||||||
| return DxlError::BULK_READ_FAIL; | ||||||||
| } | ||||||||
|
|
@@ -1027,9 +1029,8 @@ DxlError Dynamixel::ProcessReadData( | |||||||
| id, | ||||||||
| static_cast<int32_t>(dxl_getdata)); | ||||||||
| } else if (item_names[item_index] == "Present Velocity") { | ||||||||
| *data_ptrs[item_index] = dxl_info_.ConvertValueRPMToVelocityRPS( | ||||||||
| id, | ||||||||
| static_cast<int32_t>(dxl_getdata)); | ||||||||
| *data_ptrs[item_index] = | ||||||||
| dxl_info_.ConvertValueRPMToVelocityRPS(static_cast<int32_t>(dxl_getdata)); | ||||||||
| } else if (item_names[item_index] == "Present Current") { | ||||||||
| *data_ptrs[item_index] = dxl_info_.ConvertCurrentToEffort( | ||||||||
| id, | ||||||||
|
|
@@ -1173,7 +1174,7 @@ DxlError Dynamixel::SetDxlValueToSyncWrite() | |||||||
| param_write_value[added_byte + 0] = DXL_LOBYTE(goal_current); | ||||||||
| param_write_value[added_byte + 1] = DXL_HIBYTE(goal_current); | ||||||||
| } else if (indirect_info_write_[ID].item_name.at(item_index) == "Goal Velocity") { | ||||||||
| int16_t goal_velocity = dxl_info_.ConvertVelocityRPSToValueRPM(ID, data); | ||||||||
| int16_t goal_velocity = dxl_info_.ConvertVelocityRPSToValueRPM(data); | ||||||||
| param_write_value[added_byte + 0] = DXL_LOBYTE(DXL_LOWORD(goal_velocity)); | ||||||||
| param_write_value[added_byte + 1] = DXL_HIBYTE(DXL_LOWORD(goal_velocity)); | ||||||||
| param_write_value[added_byte + 2] = DXL_LOBYTE(DXL_HIWORD(goal_velocity)); | ||||||||
|
|
@@ -1288,7 +1289,7 @@ DxlError Dynamixel::SetDxlValueToBulkWrite() | |||||||
| param_write_value[added_byte + 0] = DXL_LOBYTE(goal_current); | ||||||||
| param_write_value[added_byte + 1] = DXL_HIBYTE(goal_current); | ||||||||
| } else if (indirect_info_write_[ID].item_name.at(item_index) == "Goal Velocity") { | ||||||||
| int32_t goal_velocity = dxl_info_.ConvertVelocityRPSToValueRPM(ID, data); | ||||||||
| int32_t goal_velocity = dxl_info_.ConvertVelocityRPSToValueRPM(data); | ||||||||
| param_write_value[added_byte + 0] = DXL_LOBYTE(DXL_LOWORD(goal_velocity)); | ||||||||
| param_write_value[added_byte + 1] = DXL_HIBYTE(DXL_LOWORD(goal_velocity)); | ||||||||
| param_write_value[added_byte + 2] = DXL_LOBYTE(DXL_HIWORD(goal_velocity)); | ||||||||
|
|
||||||||
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Consider using
static_cast<long>to explicitly castread_data_list_.size()tolongto avoid potential compiler warnings or errors. It is generally safer to use%ldforsize_tassize_tis an unsigned type, and%dis for signed integers.