-
Notifications
You must be signed in to change notification settings - Fork 12
Bump 1.4.10 #67
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.10 #67
Changes from all commits
5fe935a
3dc9b00
bba2456
89ad779
9b25da6
d8b7687
a3a5325
8469698
db3dd4e
5697918
fa57a41
f35f3ea
f60627c
e927501
9ca2fa3
433071d
0e5cf24
67c4dab
152a338
2fd4c4b
73687aa
ccb8c01
cc338de
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 | ||||||||||||||||||||
|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
|
@@ -40,16 +40,16 @@ typedef struct | |||||||||||||||||||||
|
|
||||||||||||||||||||||
| typedef struct | ||||||||||||||||||||||
| { | ||||||||||||||||||||||
| double torque_constant; | ||||||||||||||||||||||
| double min_radian; | ||||||||||||||||||||||
| double max_radian; | ||||||||||||||||||||||
| int32_t value_of_zero_radian_position; | ||||||||||||||||||||||
| int32_t value_of_max_radian_position; | ||||||||||||||||||||||
| int32_t value_of_min_radian_position; | ||||||||||||||||||||||
| uint16_t model_num; | ||||||||||||||||||||||
| double velocity_unit; | ||||||||||||||||||||||
|
|
||||||||||||||||||||||
| std::vector<ControlItem> item; | ||||||||||||||||||||||
| std::map<std::string, double> unit_map; | ||||||||||||||||||||||
| std::map<std::string, bool> sign_type_map; | ||||||||||||||||||||||
| } DxlInfo; | ||||||||||||||||||||||
|
|
||||||||||||||||||||||
| class DynamixelInfo | ||||||||||||||||||||||
|
|
@@ -73,27 +73,45 @@ class DynamixelInfo | |||||||||||||||||||||
| void ReadDxlModelFile(uint8_t id, uint16_t model_num); | ||||||||||||||||||||||
| bool GetDxlControlItem(uint8_t id, std::string item_name, uint16_t & addr, uint8_t & size); | ||||||||||||||||||||||
| bool CheckDxlControlItem(uint8_t id, std::string item_name); | ||||||||||||||||||||||
| // bool GetDxlTypeInfo( | ||||||||||||||||||||||
| // uint8_t id, | ||||||||||||||||||||||
| // int32_t & value_of_zero_radian_position, | ||||||||||||||||||||||
| // int32_t & value_of_max_radian_position, | ||||||||||||||||||||||
| // int32_t & value_of_min_radian_position, | ||||||||||||||||||||||
| // double & min_radian, | ||||||||||||||||||||||
| // double & max_radian, | ||||||||||||||||||||||
| // double & torque_constant, | ||||||||||||||||||||||
| // double & velocity_unit); | ||||||||||||||||||||||
|
|
||||||||||||||||||||||
| bool GetDxlUnitValue(uint8_t id, std::string data_name, double & unit_value); | ||||||||||||||||||||||
| bool GetDxlSignType(uint8_t id, std::string data_name, bool & is_signed); | ||||||||||||||||||||||
|
|
||||||||||||||||||||||
| // Template-based conversion methods | ||||||||||||||||||||||
| template<typename T> | ||||||||||||||||||||||
| double ConvertValueToUnit(uint8_t id, std::string data_name, T value); | ||||||||||||||||||||||
|
|
||||||||||||||||||||||
| template<typename T> | ||||||||||||||||||||||
| T ConvertUnitToValue(uint8_t id, std::string data_name, double unit_value); | ||||||||||||||||||||||
|
Comment on lines
+81
to
+85
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. The
Suggested change
|
||||||||||||||||||||||
|
|
||||||||||||||||||||||
| // Helper method for internal use | ||||||||||||||||||||||
| double GetUnitMultiplier(uint8_t id, std::string data_name); | ||||||||||||||||||||||
|
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. |
||||||||||||||||||||||
|
|
||||||||||||||||||||||
| int32_t ConvertRadianToValue(uint8_t id, double radian); | ||||||||||||||||||||||
| double ConvertValueToRadian(uint8_t id, int32_t value); | ||||||||||||||||||||||
| inline int16_t ConvertEffortToCurrent(uint8_t id, double effort) | ||||||||||||||||||||||
| {return static_cast<int16_t>(effort / dxl_info_[id].torque_constant);} | ||||||||||||||||||||||
| inline double ConvertCurrentToEffort(uint8_t id, int16_t current) | ||||||||||||||||||||||
| {return static_cast<double>(current * dxl_info_[id].torque_constant);} | ||||||||||||||||||||||
| inline double ConvertValueRPMToVelocityRPS(uint8_t id, int32_t value_rpm) | ||||||||||||||||||||||
| {return static_cast<double>(value_rpm * dxl_info_[id].velocity_unit / 60.0 * 2.0 * M_PI);} | ||||||||||||||||||||||
| inline int32_t ConvertVelocityRPSToValueRPM(uint8_t id, double vel_rps) | ||||||||||||||||||||||
| {return static_cast<int32_t>(vel_rps / dxl_info_[id].velocity_unit * 60.0 / 2.0 / M_PI);} | ||||||||||||||||||||||
| }; | ||||||||||||||||||||||
|
|
||||||||||||||||||||||
| // Template implementations | ||||||||||||||||||||||
| template<typename T> | ||||||||||||||||||||||
| double DynamixelInfo::ConvertValueToUnit(uint8_t id, std::string data_name, T value) | ||||||||||||||||||||||
|
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. The
Suggested change
|
||||||||||||||||||||||
| { | ||||||||||||||||||||||
| auto it = dxl_info_[id].unit_map.find(data_name); | ||||||||||||||||||||||
| if (it != dxl_info_[id].unit_map.end()) { | ||||||||||||||||||||||
| return static_cast<double>(value) * it->second; | ||||||||||||||||||||||
| } | ||||||||||||||||||||||
| return static_cast<double>(value); | ||||||||||||||||||||||
| } | ||||||||||||||||||||||
|
|
||||||||||||||||||||||
| template<typename T> | ||||||||||||||||||||||
| T DynamixelInfo::ConvertUnitToValue(uint8_t id, std::string data_name, double unit_value) | ||||||||||||||||||||||
|
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. The
Suggested change
|
||||||||||||||||||||||
| { | ||||||||||||||||||||||
| auto it = dxl_info_[id].unit_map.find(data_name); | ||||||||||||||||||||||
| if (it != dxl_info_[id].unit_map.end()) { | ||||||||||||||||||||||
| return static_cast<T>(unit_value / it->second); | ||||||||||||||||||||||
| } | ||||||||||||||||||||||
| return static_cast<T>(unit_value); | ||||||||||||||||||||||
| } | ||||||||||||||||||||||
|
|
||||||||||||||||||||||
| } // namespace dynamixel_hardware_interface | ||||||||||||||||||||||
|
|
||||||||||||||||||||||
| #endif // DYNAMIXEL_HARDWARE_INTERFACE__DYNAMIXEL__DYNAMIXEL_INFO_HPP_ | ||||||||||||||||||||||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -2,7 +2,7 @@ | |
| <?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?> | ||
| <package format="3"> | ||
| <name>dynamixel_hardware_interface</name> | ||
| <version>1.4.9</version> | ||
| <version>1.4.10</version> | ||
| <description> | ||
| ROS 2 package providing a hardware interface for controlling Dynamixel motors via the ROS 2 control framework. | ||
| </description> | ||
|
|
@@ -12,16 +12,20 @@ | |
| <author email="[email protected]">Sungho Woo</author> | ||
| <author email="[email protected]">Woojin Wie</author> | ||
| <author email="[email protected]">Wonho Yun</author> | ||
|
|
||
| <buildtool_depend>ament_cmake</buildtool_depend> | ||
|
|
||
| <depend>rclcpp</depend> | ||
| <depend>hardware_interface</depend> | ||
| <depend>pluginlib</depend> | ||
| <depend>realtime_tools</depend> | ||
| <depend>dynamixel_sdk</depend> | ||
| <depend>std_srvs</depend> | ||
| <depend>dynamixel_interfaces</depend> | ||
|
|
||
| <test_depend>ament_lint_auto</test_depend> | ||
| <test_depend>ament_lint_common</test_depend> | ||
|
|
||
| <export> | ||
| <build_type>ament_cmake</build_type> | ||
| </export> | ||
|
|
||
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.
The
data_nameparameter is passed by value, which can cause unnecessary string copies and impact performance. It's better to pass it byconstreference.