Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ class OpenArm_v10HW : public hardware_interface::SystemInterface {
const uint32_t DEFAULT_GRIPPER_RECV_CAN_ID = 0x18;

// 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};
const std::vector<double> DEFAULT_KD = {2.75, 2.5, 0.7, 0.4,
0.7, 0.6, 0.5, 0.1};
Expand Down
5 changes: 2 additions & 3 deletions openarm_hardware/src/v10_simple_hardware.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -230,9 +230,8 @@ hardware_interface::return_type OpenArm_v10HW::read(
const rclcpp::Time& /*time*/, const rclcpp::Duration& /*period*/) {
// Receive all motor states
openarm_->set_callback_mode_all(openarm::damiao_motor::CallbackMode::STATE);
openarm_->refresh_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
const auto& arm_motors = openarm_->get_arm().get_motors();
Expand Down Expand Up @@ -272,9 +271,9 @@ hardware_interface::return_type OpenArm_v10HW::write(
openarm_->get_arm().mit_control_all(arm_params);
// Control gripper if enabled
if (hand_ && joint_names_.size() > ARM_DOF) {
// TODO the mappings are unimplemented.
// Convert joint value (0-1) to motor position (radians)
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}});
Copy link

Copilot AI Jul 23, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The magic numbers {5.0, 1.0, motor_command, 0, 0} should be replaced with named constants or variables to improve code readability and maintainability. Consider defining constants like GRIPPER_KP, GRIPPER_KD, etc.

Suggested change
openarm_->get_gripper().mit_control_all({{5.0, 1.0, motor_command, 0, 0}});
openarm_->get_gripper().mit_control_all({{GRIPPER_KP, GRIPPER_KD, motor_command, GRIPPER_VELOCITY, GRIPPER_TORQUE}});

Copilot uses AI. Check for mistakes.
}
std::this_thread::sleep_for(std::chrono::microseconds(300));
Expand Down