${arm_type} mock_components/GenericSystem ${fake_sensor_commands} 0.0 openarm_hardware/OpenArm_v10HW ${left_can_interface} ${left_arm_prefix} ${hand} ${can_fd} ${gravity_compensation_enabled} ${gravity_compensation_use_kdl} ${gravity_torque_mode} ${gravity_scale} ${gravity_tau_limit1} ${gravity_tau_limit2} ${gravity_tau_limit3} ${gravity_tau_limit4} ${gravity_tau_limit5} ${gravity_tau_limit6} ${gravity_tau_limit7} ${kdl_urdf_path} ${kdl_base_link} ${kdl_tip_link if kdl_tip_link != '' else 'openarm_' + left_arm_prefix + 'link7'} ${control_gains['joint1']['kp']} ${control_gains['joint2']['kp']} ${control_gains['joint3']['kp']} ${control_gains['joint4']['kp']} ${control_gains['joint5']['kp']} ${control_gains['joint6']['kp']} ${control_gains['joint7']['kp']} ${control_gains['joint1']['kd']} ${control_gains['joint2']['kd']} ${control_gains['joint3']['kd']} ${control_gains['joint4']['kd']} ${control_gains['joint5']['kd']} ${control_gains['joint6']['kd']} ${control_gains['joint7']['kd']} ${initial_position} 0.0 0.0 ${arm_type} mock_components/GenericSystem ${fake_sensor_commands} 0.0 openarm_hardware/OpenArm_v10HW ${right_can_interface} ${right_arm_prefix} ${hand} ${can_fd} ${gravity_compensation_enabled} ${gravity_compensation_use_kdl} ${gravity_torque_mode} ${gravity_scale} ${gravity_tau_limit1} ${gravity_tau_limit2} ${gravity_tau_limit3} ${gravity_tau_limit4} ${gravity_tau_limit5} ${gravity_tau_limit6} ${gravity_tau_limit7} ${kdl_urdf_path} ${kdl_base_link} ${kdl_tip_link if kdl_tip_link != '' else 'openarm_' + right_arm_prefix + 'link7'} ${control_gains['joint1']['kp']} ${control_gains['joint2']['kp']} ${control_gains['joint3']['kp']} ${control_gains['joint4']['kp']} ${control_gains['joint5']['kp']} ${control_gains['joint6']['kp']} ${control_gains['joint7']['kp']} ${control_gains['joint1']['kd']} ${control_gains['joint2']['kd']} ${control_gains['joint3']['kd']} ${control_gains['joint4']['kd']} ${control_gains['joint5']['kd']} ${control_gains['joint6']['kd']} ${control_gains['joint7']['kd']}