diff --git a/openarm_hardware/include/openarm_hardware/v10_simple_hardware.hpp b/openarm_hardware/include/openarm_hardware/v10_simple_hardware.hpp index 1130df2..a59428d 100644 --- a/openarm_hardware/include/openarm_hardware/v10_simple_hardware.hpp +++ b/openarm_hardware/include/openarm_hardware/v10_simple_hardware.hpp @@ -138,6 +138,7 @@ class OpenArm_v10HW : public hardware_interface::SystemInterface { void return_to_zero(); bool parse_config(const hardware_interface::HardwareInfo& info); void generate_joint_names(); + void set_current_pose(); // Gripper mapping functions double joint_to_motor_radians(double joint_value); diff --git a/openarm_hardware/src/v10_simple_hardware.cpp b/openarm_hardware/src/v10_simple_hardware.cpp index 2ddaeac..20606e3 100644 --- a/openarm_hardware/src/v10_simple_hardware.cpp +++ b/openarm_hardware/src/v10_simple_hardware.cpp @@ -224,8 +224,7 @@ hardware_interface::CallbackReturn OpenArm_v10HW::on_activate( std::this_thread::sleep_for(std::chrono::milliseconds(100)); openarm_->recv_all(); - // Return to zero position - return_to_zero(); + set_current_pose(); RCLCPP_INFO(rclcpp::get_logger("OpenArm_v10HW"), "OpenArm V10 activated"); return CallbackReturn::SUCCESS; @@ -317,6 +316,20 @@ void OpenArm_v10HW::return_to_zero() { openarm_->recv_all(); } +void OpenArm_v10HW::set_current_pose() { + RCLCPP_INFO(rclcpp::get_logger("OpenArm_v10HW"), + "Setting current position..."); + + // Use read() to populate state arrays + read(rclcpp::Time(), rclcpp::Duration(0, 0)); + + // Copy current states to commands and zero velocities/torques + for (size_t i = 0; i < joint_names_.size(); ++i) { + pos_commands_[i] = pos_states_[i]; + vel_commands_[i] = 0.0; + tau_commands_[i] = 0.0; + } +} // Gripper mapping helper functions double OpenArm_v10HW::joint_to_motor_radians(double joint_value) { // Joint 0=closed -> motor 0 rad, Joint 0.044=open -> motor -1.0472 rad