diff --git a/openarm_hardware/include/openarm_hardware/v10_simple_hardware.hpp b/openarm_hardware/include/openarm_hardware/v10_simple_hardware.hpp index 64f85f3..d9e2b29 100644 --- a/openarm_hardware/include/openarm_hardware/v10_simple_hardware.hpp +++ b/openarm_hardware/include/openarm_hardware/v10_simple_hardware.hpp @@ -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 DEFAULT_KP = {80.0, 80.0, 20.0, 55.0, + const std::vector DEFAULT_KP = {20.0, 20.0, 20.0, 20.0, 5.0, 5.0, 5.0, 0.5}; const std::vector DEFAULT_KD = {2.75, 2.5, 0.7, 0.4, 0.7, 0.6, 0.5, 0.1}; diff --git a/openarm_hardware/src/v10_simple_hardware.cpp b/openarm_hardware/src/v10_simple_hardware.cpp index 944b094..bfe2cce 100644 --- a/openarm_hardware/src/v10_simple_hardware.cpp +++ b/openarm_hardware/src/v10_simple_hardware.cpp @@ -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(); @@ -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}}); } std::this_thread::sleep_for(std::chrono::microseconds(300));