Skip to content
This repository has been archived by the owner on Dec 13, 2024. It is now read-only.

Commit

Permalink
Fixes to mobile manipulation config (#345)
Browse files Browse the repository at this point in the history
* fixes to mobile manipulation config

* run pre-commit

---------

Co-authored-by: Michael Wrock <mike.wrock@gmail.com>
  • Loading branch information
marioprats and MikeWrock authored Aug 15, 2024
1 parent 0f2b3dc commit 2ed27a5
Showing 1 changed file with 42 additions and 27 deletions.
69 changes: 42 additions & 27 deletions src/picknik_ur_mobile_config/description/ur5e.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,6 @@
<general ctrlrange="-3.1415 3.1415"/>
</default>
</default>
<default class="size1">
<general gainprm="500" biasprm="0 -500 -100" forcerange="-28 28"/>
</default>
<default class="visual">
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
</default>
Expand Down Expand Up @@ -68,12 +65,16 @@
<default class="robot">
<material specular="0.5" shininess="0.25"/>
<joint armature="0.1" damping="1" axis="0 0 1" range="-2.8973 2.8973"/>
<general dyntype="none" biastype="affine" ctrlrange="-3.14159 3.14159" forcerange="-5000 5000"/>
<general dyntype="none" biastype="affine" ctrlrange="-3.14159 3.14159" forcerange="-50000 50000"/>
<default class="limitedJoints">
<joint limited="true"/>
</default>
<site size="0.001" rgba="0.5 0.5 0.5 0.3" group="4"/>
</default>
<default class="rail">
<joint armature="0.1" damping="1" axis="0 0 1" range="-5.0 5.0"/>
<general dyntype="none" biastype="affine" ctrlrange="-5.0 5.0" forcerange="-50000 50000"/>
</default>

</default>
<asset>
Expand Down Expand Up @@ -124,10 +125,9 @@
<light name="spotlight" mode="targetbodycom" target="wrist_2_link" pos="0 -1 2"/>

<site name="scene_camera_optical_frame" pos="0.0 -2.0 3.5" euler="3.64 0.0 0.0"/>
<camera name="scene_camera" pos="0.0 -2.0 3.5" fovy="58" mode="fixed" resolution="640 480" euler="0.5 0.0 0.0"/>
<camera name="scene_camera" pos="0.5 -4.0 3.5" fovy="58" mode="fixed" resolution="640 480" euler="0.8 -0.4 -0.2"/>
<body name="base_platform_rotation" pos="0 0 0" euler="0 0 0">
<inertial mass="10.0" pos="0 0 0" diaginertia="0.001 0.001 0.001"/>
<joint name="rotational_yaw_joint" class="size3" axis="0 0 1"/>
<body name="base_platform" pos="0 0 0" euler="0 0 0">
<body name="ridgeback_base_link">
<geom name="chassis_link" mesh="chassis_link" material="black" type="mesh" contype="0" conaffinity="0" group="2"/>
Expand Down Expand Up @@ -159,6 +159,7 @@
</body>
<joint name="linear_x_joint" type="slide" axis="1 0 0" range="-5.0 5.0"/>
<joint name="linear_y_joint" type="slide" axis="0 1 0" range="-5.0 5.0"/>
<joint name="rotational_yaw_joint" axis="0 0 1"/>
<body name="base" pos="0.0 0.0 0.28" euler="0 0 0" childclass="ur5e">
<inertial mass="4.0" pos="0 0 0" diaginertia="0.00443333156 0.00443333156 0.0072"/>
<geom mesh="base_0" material="black" class="visual"/>
Expand Down Expand Up @@ -190,14 +191,14 @@
<geom class="collision" size="0.038 0.19" pos="0 0 0.2"/>
<body name="wrist_1_link" pos="0 0 0.392" quat="1 0 1 0">
<inertial mass="1.219" pos="0 0.127 0" diaginertia="0.0025599 0.0025599 0.0021942"/>
<joint name="wrist_1_joint" class="size1"/>
<joint name="wrist_1_joint" class="size3"/>
<geom mesh="wrist1_0" material="black" class="visual"/>
<geom mesh="wrist1_1" material="urblue" class="visual"/>
<geom mesh="wrist1_2" material="jointgray" class="visual"/>
<geom class="collision" pos="0 0.05 0" quat="1 1 0 0" size="0.04 0.07"/>
<body name="wrist_2_link" pos="0 0.127 0">
<inertial mass="1.219" pos="0 0 0.1" diaginertia="0.0025599 0.0025599 0.0021942"/>
<joint name="wrist_2_joint" axis="0 0 1" class="size1"/>
<joint name="wrist_2_joint" axis="0 0 1" class="size3"/>
<geom mesh="wrist2_0" material="black" class="visual"/>
<geom mesh="wrist2_1" material="urblue" class="visual"/>
<geom mesh="wrist2_2" material="jointgray" class="visual"/>
Expand All @@ -206,7 +207,7 @@
<body name="wrist_3_link" pos="0 0 0.1">
<inertial mass="0.1889" pos="0 0.0771683 0" quat="1 0 0 1"
diaginertia="0.000132134 9.90863e-05 9.90863e-05"/>
<joint name="wrist_3_joint" class="size1"/>
<joint name="wrist_3_joint" class="size3"/>
<geom material="linkgray" mesh="wrist3" class="visual"/>
<!-- <geom class="eef_collision" pos="0 0.08 0" quat="1 1 0 0" size="0.04 0.02"/> -->
<site name="attachment_site" pos="0 0.1 0" quat="-1 1 0 0"/>
Expand Down Expand Up @@ -313,26 +314,26 @@
</worldbody>

<actuator>
<general class="size3" name="shoulder_pan_joint" joint="shoulder_pan_joint"/>
<general class="size3" name="shoulder_lift_joint" joint="shoulder_lift_joint"/>
<general class="size3_limited" name="elbow_joint" joint="elbow_joint"/>
<general class="size1" name="wrist_1_joint" joint="wrist_1_joint"/>
<general class="size1" name="wrist_2_joint" joint="wrist_2_joint"/>
<general class="size1" name="wrist_3_joint" joint="wrist_3_joint"/>
<position class="rail" name="linear_x_joint" joint="linear_x_joint" kp="75000" dampratio="1.0"/>
<position class="rail" name="linear_y_joint" joint="linear_y_joint" kp="75000" dampratio="1.0"/>
<position class="robot" name="rotational_yaw_joint" joint="rotational_yaw_joint" kp="75000" dampratio="1.0"/>
</actuator>

<actuator>
<general class="size3" name="shoulder_pan_joint" joint="shoulder_pan_joint" gainprm="75000" biasprm="0 -75000 -15000"/>
<general class="size3" name="shoulder_lift_joint" joint="shoulder_lift_joint" gainprm="75000" biasprm="0 -75000 -15000"/>
<general class="size3_limited" name="elbow_joint" joint="elbow_joint" gainprm="75000" biasprm="0 -75000 -15000"/>
<general class="size3" name="wrist_1_joint" joint="wrist_1_joint" gainprm="50000" biasprm="0 -50000 -10000"/>
<general class="size3" name="wrist_2_joint" joint="wrist_2_joint" gainprm="50000" biasprm="0 -50000 -10000"/>
<general class="size3" name="wrist_3_joint" joint="wrist_3_joint" gainprm="50000" biasprm="0 -50000 -10000"/>
<general class="2f85" name="robotiq_85_left_knuckle_joint" tendon="split" forcerange="-5 5" ctrlrange="0 .8"
gainprm="100 0 0" biasprm="0 -100 -150"/>
</actuator>


<contact>
<exclude body1="base_platform" body2="base"/>
</contact>

<actuator>
<general class="robot" name="linear_x_joint" joint="linear_x_joint" gainprm="2500" biasprm="0 -2500 -2000"/>
<general class="robot" name="linear_y_joint" joint="linear_y_joint" gainprm="2500" biasprm="0 -2500 -2000"/>
<general class="size3" name="rotational_yaw_joint" joint="rotational_yaw_joint"/>
</actuator>
<contact>
<exclude body1="base_platform" body2="base"/>
</contact>

<!-- Robotiq gripper contact -->
<contact>
Expand Down Expand Up @@ -362,7 +363,21 @@
<torque name="ee_torque_sensor" site="robotiq_ft_sensor" />
</sensor>

<!--<keyframe>
<key qpos='0.0 0.0 0.0 2.74488e-10 2.74488e-10 -3.73952e-10 -3.73952e-10 -0.31415 -1.37115 0.981361 -1.75672 -1.57075 -3.26716 0.0203697 0.000532128 0.0216355 -0.0224045 0.0203839 0.000542834 0.0216769 -0.0224794'/>
</keyframe> -->
<keyframe>
<!-- qpos -->
<!-- front_rocker, front_left_wheel, front_right_wheel, rear_left_wheel, rear_right_wheel -->
<!-- linear_x_joint, linear_y_joint, rotational_yaw_joint, shoulder_pan, shoulder_lift, elbow, wrist_1, wrist_2, wrist_3 -->
<!-- right_knuckle, right_finger, right_inner_knuckle, right_finger_tip, left_knuckle, left_finger, left_inner_knuckle, left_finger_tip -->
<!-- ctrl -->
<!-- linear_x_joint, linear_y_joint, rotational_yaw_joint, shoulder_pan, shoulder_lift, elbow, wrist_1, wrist_2, wrist_3, robotiq_85_left_knuckle_joint -->
<key qpos="
0 0 0 0 0
0 0 0 0 -1.534 0.8197 -2.2686 -1.57076 0
0 0 0 0 0 0 0 0
"
ctrl="
0 0 0 0 -1.534 0.8197 -2.2686 -1.57076 0 0
"
/>
</keyframe>
</mujoco>

0 comments on commit 2ed27a5

Please sign in to comment.