diff --git a/urdf/ur.ros2_control.xacro b/urdf/ur.ros2_control.xacro index f1050ab..0a57abc 100644 --- a/urdf/ur.ros2_control.xacro +++ b/urdf/ur.ros2_control.xacro @@ -75,6 +75,17 @@ + + + 4000.0 + 250.0 + 1.0 + 15.0 + -15.0 + 150.0 + -150.0 + 0.0 + @@ -91,6 +102,17 @@ + + + 100000.0 + 1600.0 + 2.5 + 45.0 + -45.0 + 150.0 + -150.0 + 0.0 + @@ -107,6 +129,17 @@ + + + 10000.0 + 450.0 + 2.0 + 30.0 + -30.0 + 150.0 + -150.0 + 0.0 + @@ -123,6 +156,17 @@ + + + 3000.0 + 175.0 + 0.5 + 7.0 + -7.0 + 28.0 + -28.0 + 0.0 + @@ -139,6 +183,17 @@ + + + 2500.0 + 150.0 + 0.3 + 6.0 + -6.0 + 28.0 + -28.0 + 0.0 + @@ -155,6 +210,17 @@ + + + 2000.0 + 10.0 + 0.2 + 5.0 + -5.0 + 28.0 + -28.0 + 0.0 + diff --git a/urdf/ur_macro.xacro b/urdf/ur_macro.xacro index 7e43bcd..a65c8b3 100644 --- a/urdf/ur_macro.xacro +++ b/urdf/ur_macro.xacro @@ -70,6 +70,7 @@ fake_sensor_commands:=false sim_gazebo:=false sim_ignition:=false + force_abs_paths:=false headless_mode:=false initial_positions:=${dict(shoulder_pan_joint=0.0,shoulder_lift_joint=-1.57,elbow_joint=0.0,wrist_1_joint=-1.57,wrist_2_joint=0.0,wrist_3_joint=0.0)} use_tool_communication:=false @@ -96,7 +97,7 @@ kinematics_parameters_file="${kinematics_parameters_file}" physical_parameters_file="${physical_parameters_file}" visual_parameters_file="${visual_parameters_file}" - force_abs_paths="${sim_gazebo or sim_ignition}"/> + force_abs_paths="${force_abs_paths}"/> @@ -288,7 +289,7 @@ - + @@ -300,7 +301,7 @@ - + @@ -312,7 +313,7 @@ - + @@ -324,7 +325,7 @@ - + @@ -336,7 +337,7 @@ - + @@ -348,7 +349,7 @@ - +