Code Monkey home page Code Monkey logo

dynamic_calibration's Issues

How to use the solver-sdpt3

When I run the ur_idntfcn_real.m,the parameter pib_SDP is calculated by sol2 = optimize(cnstr, obj, sdpsettings('solver','sdpt3'));.but the values of pib_SDP are NaN.
should I use the function function [obj,X,y,Z,info,runhist] = sdpt3(blk,At,C,b,OPTIONS,X0,y0,Z0)?

Questions about sol.pi_s Order and pi_full Parameter

Hi,

I have a question regarding the sol.pi_s parameter in your code. Could you please clarify the order of elements in sol.pi_s? Specifically, what do the first 9 numbers represent, and why is each group comprised of 11 numbers?

Additionally, in your previous response, you mentioned that in the experiment_design.m file, there is a vector of full parameters called pi_full. However, I was unable to locate the pi_full parameter in that file. Could you please provide more details on where to find it?

If I understand correctly, sol.pi_s represents the full parameters, right?

Thank you!
Best regards

what special need to modify the URDF file when identify other robots

Hello! this is a great paper I have read and help me a lot, thank you a lot!
I have some questions now : may I ask, if I want to identify other UR series of robots(such as ur16e , ur3e), what special need to modify the URDF file.
in my job , I get the urdf file use the script rosrun xacro xacro ur16e.xcaro > ur16e.urdf ,
ur16e.xcaro come from this url : https://github.com/fmauch/universal_robot/tree/calibration_devel
when I try to do the same work on the ur16e robot , I find that the some drive gains are negative
I am not sure if my urdf file is configured correctly, so I want to ask for your help , do URDF files need special modification somewhere?

this is the ur10e.urdf file in your work:

<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- |    This document was autogenerated by xacro from ur10e_robot.urdf.xacro         | -->
<!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
<!-- =================================================================================== -->
<robot name="ur10e" xmlns:xacro="http://ros.org/wiki/xacro">
  <gazebo>
    <plugin filename="libgazebo_ros_control.so" name="ros_control">
      <!--robotNamespace>/</robotNamespace-->
      <!--robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType-->
    </plugin>
    <!--
    <plugin name="gazebo_ros_power_monitor_controller" filename="libgazebo_ros_power_monitor.so">
      <alwaysOn>true</alwaysOn>
      <updateRate>1.0</updateRate>
      <timeout>5</timeout>
      <powerStateTopic>power_state</powerStateTopic>
      <powerStateRate>10.0</powerStateRate>
      <fullChargeCapacity>87.78</fullChargeCapacity>     
      <dischargeRate>-474</dischargeRate>
      <chargeRate>525</chargeRate>
      <dischargeVoltage>15.52</dischargeVoltage>
      <chargeVoltage>16.41</chargeVoltage>
    </plugin>
-->
  </gazebo>
  <!--
  Author: Kelsey Hawkins
  Contributers: Jimmy Da Silva, Ajit Krisshna N L, Muhammad Asif Rana
-->
  <link name="base_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_e_description/meshes/ur10e/visual/base.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_e_description/meshes/ur10e/collision/base.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="4.0"/>
      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
      <inertia ixx="0.0061063308908" ixy="0.0" ixz="0.0" iyy="0.0061063308908" iyz="0.0" izz="0.01125"/>
    </inertial>
  </link>
  <joint name="shoulder_pan_joint" type="revolute">
    <parent link="base_link"/>
    <child link="shoulder_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.181"/>
    <axis xyz="0 0 1"/>
    <limit effort="330.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.14"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="shoulder_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_e_description/meshes/ur10e/visual/shoulder.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_e_description/meshes/ur10e/collision/shoulder.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="7.778"/>
      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
      <inertia ixx="0.0314743125769" ixy="0.0" ixz="0.0" iyy="0.0314743125769" iyz="0.0" izz="0.021875625"/>
    </inertial>
  </link>
  <joint name="shoulder_lift_joint" type="revolute">
    <parent link="shoulder_link"/>
    <child link="upper_arm_link"/>
    <origin rpy="0.0 1.57079632679 0.0" xyz="0.0 0.176 0.0"/>
    <axis xyz="0 1 0"/>
    <limit effort="330.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.14"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="upper_arm_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_e_description/meshes/ur10e/visual/upperarm.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_e_description/meshes/ur10e/collision/upperarm.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="12.93"/>
      <origin rpy="0 0 0" xyz="0.0 0.0 0.3065"/>
      <inertia ixx="0.42307374077" ixy="0.0" ixz="0.0" iyy="0.42307374077" iyz="0.0" izz="0.036365625"/>
    </inertial>
  </link>
  <joint name="elbow_joint" type="revolute">
    <parent link="upper_arm_link"/>
    <child link="forearm_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 -0.137 0.613"/>
    <axis xyz="0 1 0"/>
    <limit effort="150.0" lower="-3.14159265359" upper="3.14159265359" velocity="3.14"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="forearm_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_e_description/meshes/ur10e/visual/forearm.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_e_description/meshes/ur10e/collision/forearm.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="3.87"/>
      <origin rpy="0 0 0" xyz="0.0 0.0 0.2855"/>
      <inertia ixx="0.110590365764" ixy="0.0" ixz="0.0" iyy="0.110590365764" iyz="0.0" izz="0.010884375"/>
    </inertial>
  </link>
  <joint name="wrist_1_joint" type="revolute">
    <parent link="forearm_link"/>
    <child link="wrist_1_link"/>
    <origin rpy="0.0 1.57079632679 0.0" xyz="0.0 0.0 0.571"/>
    <axis xyz="0 1 0"/>
    <limit effort="54.0" lower="-6.28318530718" upper="6.28318530718" velocity="6.28"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="wrist_1_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_e_description/meshes/ur10e/visual/wrist1.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_e_description/meshes/ur10e/collision/wrist1.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="1.96"/>
      <origin rpy="0 0 0" xyz="0.0 0.135 0.0"/>
      <inertia ixx="0.0051082479567" ixy="0.0" ixz="0.0" iyy="0.0051082479567" iyz="0.0" izz="0.0055125"/>
    </inertial>
  </link>
  <joint name="wrist_2_joint" type="revolute">
    <parent link="wrist_1_link"/>
    <child link="wrist_2_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.135 0.0"/>
    <axis xyz="0 0 1"/>
    <limit effort="54.0" lower="-6.28318530718" upper="6.28318530718" velocity="6.28"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="wrist_2_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_e_description/meshes/ur10e/visual/wrist2.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_e_description/meshes/ur10e/collision/wrist2.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="1.96"/>
      <origin rpy="0 0 0" xyz="0.0 0.0 0.12"/>
      <inertia ixx="0.0051082479567" ixy="0.0" ixz="0.0" iyy="0.0051082479567" iyz="0.0" izz="0.0055125"/>
    </inertial>
  </link>
  <joint name="wrist_3_joint" type="revolute">
    <parent link="wrist_2_link"/>
    <child link="wrist_3_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.12"/>
    <axis xyz="0 1 0"/>
    <limit effort="54.0" lower="-6.28318530718" upper="6.28318530718" velocity="6.28"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="wrist_3_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_e_description/meshes/ur10e/visual/wrist3.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_e_description/meshes/ur10e/collision/wrist3.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.202"/>
      <origin rpy="1.57079632679 0 0" xyz="0.0 0.092 0.0"/>
      <inertia ixx="0.000144345775595" ixy="0.0" ixz="0.0" iyy="0.000144345775595" iyz="0.0" izz="0.000204525"/>
    </inertial>
  </link>
  <joint name="ee_fixed_joint" type="fixed">
    <parent link="wrist_3_link"/>
    <child link="ee_link"/>
    <origin rpy="0.0 0.0 1.57079632679" xyz="0.0 0.117 0.0"/>
  </joint>
  <link name="ee_link">
    <collision>
      <geometry>
        <box size="0.01 0.01 0.01"/>
      </geometry>
      <origin rpy="0 0 0" xyz="-0.01 0 0"/>
    </collision>
  </link>
  <transmission name="shoulder_pan_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="shoulder_pan_joint">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </joint>
    <actuator name="shoulder_pan_motor">
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="shoulder_lift_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="shoulder_lift_joint">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </joint>
    <actuator name="shoulder_lift_motor">
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="elbow_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="elbow_joint">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </joint>
    <actuator name="elbow_motor">
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="wrist_1_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="wrist_1_joint">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </joint>
    <actuator name="wrist_1_motor">
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="wrist_2_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="wrist_2_joint">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </joint>
    <actuator name="wrist_2_motor">
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="wrist_3_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="wrist_3_joint">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </joint>
    <actuator name="wrist_3_motor">
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <gazebo reference="shoulder_link">
    <selfCollide>true</selfCollide>
  </gazebo>
  <gazebo reference="upper_arm_link">
    <selfCollide>true</selfCollide>
  </gazebo>
  <gazebo reference="forearm_link">
    <selfCollide>true</selfCollide>
  </gazebo>
  <gazebo reference="wrist_1_link">
    <selfCollide>true</selfCollide>
  </gazebo>
  <gazebo reference="wrist_3_link">
    <selfCollide>true</selfCollide>
  </gazebo>
  <gazebo reference="wrist_2_link">
    <selfCollide>true</selfCollide>
  </gazebo>
  <gazebo reference="ee_link">
    <selfCollide>true</selfCollide>
  </gazebo>
  <!-- ROS base_link to UR 'Base' Coordinates transform -->
  <link name="base"/>
  <joint name="base_link-base_fixed_joint" type="fixed">
    <!-- NOTE: this rotation is only needed as long as base_link itself is
                 not corrected wrt the real robot (ie: rotated over 180
                 degrees)
      -->
    <origin rpy="0 0 -3.14159265359" xyz="0 0 0"/>
    <parent link="base_link"/>
    <child link="base"/>
  </joint>
  <!-- Frame coincident with all-zeros TCP on UR controller -->
  <link name="tool0"/>
  <joint name="wrist_3_link-tool0_fixed_joint" type="fixed">
    <origin rpy="-1.57079632679 0 0" xyz="0 0.117 0"/>
    <parent link="wrist_3_link"/>
    <child link="tool0"/>
  </joint>
  <link name="world"/>
  <joint name="world_joint" type="fixed">
    <parent link="world"/>
    <child link="base_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
  </joint>
</robot>

and this is I used in my work , I am not sure where I need to modify:

<?xml version="1.0" ?>

<robot name="ur10e" xmlns:xacro="http://ros.org/wiki/xacro">
  
  <!--Link-->
  <link name="base_link">
    <visual>
      <origin rpy="0 0 3.14159265359" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10e/visual/base.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 3.14159265359" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10e/collision/base.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="4.0"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="0.0061063308908" ixy="0.0" ixz="0.0" iyy="0.0061063308908" iyz="0.0" izz="0.01125"/>
    </inertial>
  </link>
    
  <link name="shoulder_link">
    <visual>
      <origin rpy="0 0 3.14159265359" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10e/visual/shoulder.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 3.14159265359" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10e/collision/shoulder.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="7.369"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="0.0298192606556" ixy="0.0" ixz="0.0" iyy="0.0298192606556" iyz="0.0" izz="0.0207253125"/>
    </inertial>
  </link>

  <link name="upper_arm_link">
    <visual>
      <origin rpy="1.57079632679 0 -1.57079632679" xyz="0 0 0.176"/>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur16e/visual/upperarm.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <origin rpy="1.57079632679 0 -1.57079632679" xyz="0 0 0.176"/>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur16e/collision/upperarm.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="10.45"/>
      <origin rpy="0 1.57079632679 0" xyz="-0.2392 0.0 0.175"/>
      <inertia ixx="0.213999856233" ixy="0.0" ixz="0.0" iyy="0.213999856233" iyz="0.0" izz="0.029390625"/>
    </inertial>
  </link>

  <link name="forearm_link">
    <visual>
      <origin rpy="1.57079632679 0 -1.57079632679" xyz="0 0 0.04"/>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur16e/visual/forearm.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <origin rpy="1.57079632679 0 -1.57079632679" xyz="0 0 0.04"/>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur16e/collision/forearm.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="4.321"/>
      <origin rpy="0 1.57079632679 0" xyz="-0.18 0.0 0.04"/>
      <inertia ixx="0.0527431851527" ixy="0.0" ixz="0.0" iyy="0.0527431851527" iyz="0.0" izz="0.0121528125"/>
    </inertial>
  </link>

  <link name="wrist_1_link">
    <visual>
      <!-- TODO: Move this to a parameter -->
      <origin rpy="1.57079632679 0 0" xyz="0 0 -0.135"/>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10e/visual/wrist1.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <origin rpy="1.57079632679 0 0" xyz="0 0 -0.135"/>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10e/collision/wrist1.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="2.18"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="0.00568162272735" ixy="0.0" ixz="0.0" iyy="0.00568162272735" iyz="0.0" izz="0.00613125"/>
    </inertial>
  </link>

  <link name="wrist_2_link">
    <visual>
      <origin rpy="0 0 0" xyz="0 0 -0.12"/>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10e/visual/wrist2.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 -0.12"/>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10e/collision/wrist2.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="2.033"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="0.0052985041306" ixy="0.0" ixz="0.0" iyy="0.0052985041306" iyz="0.0" izz="0.0057178125"/>
    </inertial>
  </link>

  <link name="wrist_3_link">
    <visual>
      <origin rpy="1.57079632679 0 0" xyz="0 0 -0.1168"/>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10e/visual/wrist3.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <origin rpy="1.57079632679 0 0" xyz="0 0 -0.1168"/>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10e/collision/wrist3.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.907"/>
      <origin rpy="0 0 0" xyz="0.0 0.0 -0.025"/>
      <inertia ixx="0.000648126824083" ixy="0.0" ixz="0.0" iyy="0.000648126824083" iyz="0.0" izz="0.0009183375"/>
    </inertial>
  </link>

  <!--考虑 删除 或 修改-->
  <link name="ee_link">
    <collision>
      <geometry>
        <box size="0.01 0.01 0.01"/>
      </geometry>
      <origin rpy="0 0 0" xyz="-0.01 0 0"/>
    </collision>
  </link>

  <joint name="shoulder_pan_joint" type="revolute">
    <parent link="base_link"/>
    <child link="shoulder_link"/>
    <origin rpy="0 0 0" xyz="0 0 0.1807"/>
    <axis xyz="0 0 1"/>
    <limit effort="330.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.14"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>


  <joint name="shoulder_lift_joint" type="revolute">
    <parent link="shoulder_link"/>
    <child link="upper_arm_link"/>
    <origin rpy="1.570796327 0 0" xyz="0 0 0"/>
    <axis xyz="0 0 1"/>
    <limit effort="330.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.14"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  
  <joint name="elbow_joint" type="revolute">
    <parent link="upper_arm_link"/>
    <child link="forearm_link"/>
    <origin rpy="0 0 0" xyz="-0.4784 0 0"/>
    <axis xyz="0 0 1"/>
    <limit effort="150.0" lower="-3.14159265359" upper="3.14159265359" velocity="3.14"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  
  <joint name="wrist_1_joint" type="revolute">
    <parent link="forearm_link"/>
    <child link="wrist_1_link"/>
    <origin rpy="0 0 0" xyz="-0.36 0 0.17415"/>
    <axis xyz="0 0 1"/>
    <limit effort="56.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.14159265359"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>

  

  <joint name="wrist_2_joint" type="revolute">
    <parent link="wrist_1_link"/>
    <child link="wrist_2_link"/>
    <origin rpy="1.570796327 0 0" xyz="0 -0.11985 -2.45816459076e-11"/>
    <axis xyz="0 0 1"/>
    <limit effort="56.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.14159265359"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>

  
  <joint name="wrist_3_joint" type="revolute">
    <parent link="wrist_2_link"/>
    <child link="wrist_3_link"/>
    <origin rpy="1.57079632659 3.14159265359 3.14159265359" xyz="0 0.11655 -2.39048045935e-11"/>
    <axis xyz="0 0 1"/>
    <limit effort="56.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.14159265359"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>

  <!--考虑删除  末端负载-->
  <joint name="ee_fixed_joint" type="fixed">
    <parent link="wrist_3_link"/>
    <child link="ee_link"/>
    <!-- <origin rpy="0.0 0.0 1.57079632679" xyz="0.0 0.117 0.0"/> -->
    <origin rpy="0.0 0.0 1.57079632679" xyz="0.0 0.0 0.1371"/>
  </joint>

  <!-- ROS base_link to UR 'Base' Coordinates transform -->
  <link name="base"/>
  <joint name="base_link-base_fixed_joint" type="fixed">
    <!-- NOTE: this rotation is only needed as long as base_link itself is
                 not corrected wrt the real robot (ie: rotated over 180
                 degrees)
      -->
    <origin rpy="0 0 3.14159265359" xyz="0 0 0"/>
    <parent link="base_link"/>
    <child link="base"/>
  </joint>
  <!-- Frame coincident with all-zeros TCP on UR controller -->
  <link name="tool0"/>
  <joint name="wrist_3_link-tool0_fixed_joint" type="fixed">
    <!-- <origin rpy="-1.57079632679 0 0" xyz="0 0.117 0"/> -->
    <origin rpy="-1.57079632679 0 0" xyz="0.0 0.0 0.1371"/>
    <parent link="wrist_3_link"/>
    <child link="tool0"/>
  </joint>
  <link name="world"/>
  <joint name="world_joint" type="fixed">
    <parent link="world"/>
    <child link="base_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
  </joint>

  <transmission name="shoulder_pan_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="shoulder_pan_joint">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </joint>
    <actuator name="shoulder_pan_motor">
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="shoulder_lift_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="shoulder_lift_joint">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </joint>
    <actuator name="shoulder_lift_motor">
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="elbow_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="elbow_joint">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </joint>
    <actuator name="elbow_motor">
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="wrist_1_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="wrist_1_joint">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </joint>
    <actuator name="wrist_1_motor">
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="wrist_2_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="wrist_2_joint">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </joint>
    <actuator name="wrist_2_motor">
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="wrist_3_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="wrist_3_joint">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </joint>
    <actuator name="wrist_3_motor">
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  
  <gazebo>
    <plugin filename="libgazebo_ros_control.so" name="ros_control">
    </plugin>
  </gazebo>
  <gazebo reference="shoulder_link">
    <selfCollide>true</selfCollide>
  </gazebo>
  <gazebo reference="upper_arm_link">
    <selfCollide>true</selfCollide>
  </gazebo>
  <gazebo reference="forearm_link">
    <selfCollide>true</selfCollide>
  </gazebo>
  <gazebo reference="wrist_1_link">
    <selfCollide>true</selfCollide>
  </gazebo>
  <gazebo reference="wrist_3_link">
    <selfCollide>true</selfCollide>
  </gazebo>
  <gazebo reference="wrist_2_link">
    <selfCollide>true</selfCollide>
  </gazebo>
  <gazebo reference="ee_link">
    <selfCollide>true</selfCollide>
  </gazebo>
</robot>

When I run the function main.m, the following error occurred

Hello! When I run the function main.m, the following error occurred. Could you please tell me how to solve it? Looking forward to your reply.
错误使用 - (line 44)
Adding NaN to an SDPVAR makes no sense.

出错 estimate_dynamic_params>physicallyConsistentEstimation (line 157)
obj = norm(Tau - Wb*[pi_b; pi_frctn]);

出错 estimate_dynamic_params (line 49)
[sol.pi_b, sol.pi_fr, sol.pi_s] =
physicallyConsistentEstimation(Tau, Wb, baseQR);

出错 main (line 40)
sol = estimate_dynamic_params(path_to_est_data, idxs, ...

How to convert from base parameter to full parameter

in this code , just estimate the base parameter is the linear combination of the independent parameters, but we need the full parameter, so I want to know how to convert from base parameters to full parameters

A question about "generate_rb_dynamics.m"

Thanks for your work, it helps me a lot. Now, I have modified the code and hope it can be applied to any degree of freedom manipulator. First, I tried to apply it in a 7DOF manipulator, whose urdf file was generated by myself. I am currently facing two issues and would like to seek your advice

  1. Regressor was generated by "generate_rb_regressor.m", when run "test_rb_inverse_dynamics.m", I found that the value of "norm(tau_matlab - tau_reg)" is about 0.003, bigger than 1e-08, does it reasonable?
  2. When I run "experiment_design.m", the program has been running for about 14 hours and still hasn't ended. My cpu is "core i9 12900K". I think there may be some issues with the process of generating my regressor.
    So ,can you help me, thank you a lot.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.