-
Notifications
You must be signed in to change notification settings - Fork 12
Bump 1.4.7 #51
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.7 #51
Changes from all commits
ba695c9
013ee93
28c35b6
06e8de3
3dae77e
bb268c6
ed1d1ee
6aebda4
d157ee4
ba7957c
d88ff3b
6f696f4
00f7d86
4392276
bf0452f
6e1ed52
44d3f8f
7e20f4e
f9d5233
1d790f7
4be96ec
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 |
|---|---|---|
|
|
@@ -47,6 +47,7 @@ typedef struct | |
| 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; | ||
| } DxlInfo; | ||
|
|
@@ -72,24 +73,25 @@ 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); | ||
| // 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); | ||
|
Comment on lines
+76
to
+84
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. |
||
| 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(int32_t value_rpm) | ||
| {return static_cast<double>(value_rpm * 0.01 / 60.0 * 2.0 * M_PI);} | ||
| inline int32_t ConvertVelocityRPSToValueRPM(double vel_rps) | ||
| {return static_cast<int32_t>(vel_rps * 100.0 * 60.0 / 2.0 / M_PI);} | ||
| 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);} | ||
| }; | ||
|
|
||
| } // namespace dynamixel_hardware_interface | ||
|
|
||
| Original file line number | Diff line number | Diff line change | ||||
|---|---|---|---|---|---|---|
|
|
@@ -62,6 +62,7 @@ constexpr char HW_IF_TORQUE_ENABLE[] = "torque_enable"; | |||||
| typedef struct HandlerVarType_ | ||||||
| { | ||||||
| uint8_t id; /**< ID of the Dynamixel component. */ | ||||||
| uint8_t comm_id; /**< ID of the Dynamixel to be communicated. */ | ||||||
| std::string name; /**< Name of the component. */ | ||||||
| std::vector<std::string> interface_name_vec; /**< Vector of interface names. */ | ||||||
| std::vector<std::shared_ptr<double>> value_ptr_vec; /**< Vector interface values. */ | ||||||
|
|
@@ -227,6 +228,7 @@ class DynamixelHardware : public | |||||
| std::string port_name_; | ||||||
| std::string baud_rate_; | ||||||
| std::vector<uint8_t> dxl_id_; | ||||||
| std::vector<uint8_t> virtual_dxl_id_; | ||||||
|
|
||||||
| std::vector<uint8_t> sensor_id_; | ||||||
| std::map<uint8_t /*id*/, std::string /*interface_name*/> sensor_item_; | ||||||
|
|
@@ -245,6 +247,7 @@ class DynamixelHardware : public | |||||
| std::vector<HandlerVarType> hdl_sensor_states_; | ||||||
|
|
||||||
| ///// handler controller variable | ||||||
| std::vector<HandlerVarType> hdl_gpio_controller_states_; | ||||||
| std::vector<HandlerVarType> hdl_gpio_controller_commands_; | ||||||
|
|
||||||
| bool is_set_hdl_{false}; | ||||||
|
|
@@ -262,15 +265,6 @@ class DynamixelHardware : public | |||||
| */ | ||||||
| bool initItems(const std::string & type_filter); | ||||||
|
|
||||||
| /** | ||||||
| * @brief Helper function to retry writing an item to a Dynamixel device. | ||||||
| * @param id The ID of the Dynamixel device. | ||||||
| * @param item_name The name of the item to write. | ||||||
| * @param value The value to write. | ||||||
| * @return True if write was successful, false if timeout occurred. | ||||||
| */ | ||||||
| bool retryWriteItem(uint8_t id, const std::string & item_name, uint32_t value); | ||||||
|
|
||||||
| /** | ||||||
| * @brief Initializes Dynamixel items. | ||||||
| * @return True if initialization was successful, false otherwise. | ||||||
|
|
@@ -362,7 +356,7 @@ class DynamixelHardware : public | |||||
| size_t outer_size, | ||||||
| size_t inner_size, | ||||||
| std::vector<HandlerVarType> & outer_handlers, | ||||||
| const std::vector<HandlerVarType> & inner_handlers, | ||||||
| std::vector<HandlerVarType> & inner_handlers, | ||||||
|
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. The
Suggested change
|
||||||
| double ** matrix, | ||||||
| const std::unordered_map<std::string, std::vector<std::string>> & iface_map, | ||||||
| const std::string & conversion_iface = "", | ||||||
|
|
||||||
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 declaration for
SetOperatingModeis commented out. If this function is no longer needed, it's better to remove the declaration entirely to improve code clarity and reduce dead code. If it's temporarily disabled, a// TODO: ...comment explaining why and when it might be reinstated would be helpful.