@@ -711,15 +711,21 @@ bool DynamixelHardware::InitDxlWriteItems()
711711 for (const hardware_interface::ComponentInfo & gpio : info_.gpios ) {
712712 if (gpio.command_interfaces .size ()) {
713713 uint8_t id = static_cast <uint8_t >(stoi (gpio.parameters .at (" ID" )));
714- for (auto it : gpio.command_interfaces ) {
715- HandlerVarType temp_write;
716- temp_write.id = id;
717- temp_write.name = gpio.name ;
714+ HandlerVarType temp_write;
715+ temp_write.id = id;
716+ temp_write.name = gpio.name ;
717+
718+ temp_write.interface_name_vec .push_back (" Goal Position" );
719+ temp_write.value_ptr_vec .push_back (std::make_shared<double >(0.0 ));
718720
719- temp_write.interface_name_vec .push_back (it.name );
720- temp_write.value_ptr_vec .push_back (std::make_shared<double >(0.0 ));
721- hdl_trans_commands_.push_back (temp_write);
721+ for (auto it : gpio.command_interfaces ) {
722+ if (it.name == " Goal Current" ) {
723+ temp_write.interface_name_vec .push_back (" Goal Current" );
724+ temp_write.value_ptr_vec .push_back (std::make_shared<double >(0.0 ));
725+ }
722726 }
727+
728+ hdl_trans_commands_.push_back (temp_write);
723729 }
724730 }
725731 is_set_hdl = true ;
@@ -853,14 +859,33 @@ void DynamixelHardware::CalcJointToTransmission()
853859 double value = 0.0 ;
854860 for (size_t j = 0 ; j < num_of_joints_; j++) {
855861 value += joint_to_transmission_matrix_[i][j] *
856- (*hdl_joint_commands_.at (j).value_ptr_vec .at (0 ));
862+ (*hdl_joint_commands_.at (j).value_ptr_vec .at (GOAL_POSITION_INDEX ));
857863 }
858864
859865 if (hdl_trans_commands_.at (i).name == conversion_dxl_name_) {
860866 value = prismaticToRevolute (value);
861867 }
868+ *hdl_trans_commands_.at (i).value_ptr_vec .at (GOAL_POSITION_INDEX) = value;
869+ }
862870
863- *hdl_trans_commands_.at (i).value_ptr_vec .at (0 ) = value;
871+ for (size_t i = 0 ; i < num_of_transmissions_; i++) {
872+ if (hdl_trans_commands_.at (i).interface_name_vec .size () > GOAL_CURRENT_INDEX &&
873+ hdl_trans_commands_.at (i).interface_name_vec .at (GOAL_CURRENT_INDEX) == " Goal Current" )
874+ {
875+ for (size_t j = 0 ; j < hdl_joint_commands_.size (); j++) {
876+ if (hdl_joint_commands_.at (j).interface_name_vec .size () > GOAL_CURRENT_INDEX &&
877+ hdl_joint_commands_.at (j).interface_name_vec .at (GOAL_CURRENT_INDEX) ==
878+ hardware_interface::HW_IF_EFFORT)
879+ {
880+ double value = 0.0 ;
881+ for (size_t k = 0 ; k < num_of_joints_; k++) {
882+ value += joint_to_transmission_matrix_[i][k] *
883+ (*hdl_joint_commands_.at (k).value_ptr_vec .at (GOAL_CURRENT_INDEX));
884+ }
885+ *hdl_trans_commands_.at (i).value_ptr_vec .at (GOAL_CURRENT_INDEX) = value;
886+ }
887+ }
888+ }
864889 }
865890}
866891
0 commit comments