Fix read() in hardware plugin (#47)

- Temporary fix: read method with effective refresh_all()
- Use conservative PD parameters for control
This commit is contained in:
Yue Yin 2025-07-24 12:41:06 +09:00 committed by GitHub
parent 26b7f51d3a
commit 444a998cf8
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
2 changed files with 3 additions and 4 deletions

View File

@ -100,7 +100,7 @@ class OpenArm_v10HW : public hardware_interface::SystemInterface {
const uint32_t DEFAULT_GRIPPER_RECV_CAN_ID = 0x18; const uint32_t DEFAULT_GRIPPER_RECV_CAN_ID = 0x18;
// Default gains // Default gains
const std::vector<double> DEFAULT_KP = {80.0, 80.0, 20.0, 55.0, const std::vector<double> DEFAULT_KP = {20.0, 20.0, 20.0, 20.0,
5.0, 5.0, 5.0, 0.5}; 5.0, 5.0, 5.0, 0.5};
const std::vector<double> DEFAULT_KD = {2.75, 2.5, 0.7, 0.4, const std::vector<double> DEFAULT_KD = {2.75, 2.5, 0.7, 0.4,
0.7, 0.6, 0.5, 0.1}; 0.7, 0.6, 0.5, 0.1};

View File

@ -230,9 +230,8 @@ hardware_interface::return_type OpenArm_v10HW::read(
const rclcpp::Time& /*time*/, const rclcpp::Duration& /*period*/) { const rclcpp::Time& /*time*/, const rclcpp::Duration& /*period*/) {
// Receive all motor states // Receive all motor states
openarm_->set_callback_mode_all(openarm::damiao_motor::CallbackMode::STATE); openarm_->set_callback_mode_all(openarm::damiao_motor::CallbackMode::STATE);
openarm_->refresh_all();
openarm_->recv_all(); openarm_->recv_all();
std::this_thread::sleep_for(std::chrono::microseconds(300));
openarm_->set_callback_mode_all(openarm::damiao_motor::CallbackMode::IGNORE);
// Read arm joint states // Read arm joint states
const auto& arm_motors = openarm_->get_arm().get_motors(); const auto& arm_motors = openarm_->get_arm().get_motors();
@ -272,9 +271,9 @@ hardware_interface::return_type OpenArm_v10HW::write(
openarm_->get_arm().mit_control_all(arm_params); openarm_->get_arm().mit_control_all(arm_params);
// Control gripper if enabled // Control gripper if enabled
if (hand_ && joint_names_.size() > ARM_DOF) { if (hand_ && joint_names_.size() > ARM_DOF) {
// TODO the mappings are unimplemented.
// Convert joint value (0-1) to motor position (radians) // Convert joint value (0-1) to motor position (radians)
double motor_command = joint_to_motor_radians(pos_commands_[ARM_DOF]); double motor_command = joint_to_motor_radians(pos_commands_[ARM_DOF]);
openarm_->get_gripper().mit_control_all({{5.0, 1.0, motor_command, 0, 0}}); openarm_->get_gripper().mit_control_all({{5.0, 1.0, motor_command, 0, 0}});
} }
std::this_thread::sleep_for(std::chrono::microseconds(300)); std::this_thread::sleep_for(std::chrono::microseconds(300));