Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Move end-coords of single panda and dual_panda to the center of the fingers #3

Merged
merged 2 commits into from
Oct 12, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion jsk_panda_robot/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@
```
- Notice
- `(send *ri* :recover-error)` is required every time when you press and release the black switch (`activated` -> `monitored stop` -> `activated`).
- `dual_panda`'s `end-coords`, `reset-pose`, and `reset-manip-pose` are different from single `panda`'s ones for historical reasons.
- `dual_panda`'s `reset-pose` and `reset-manip-pose` are different from single `panda`'s ones for historical reasons.
#### Record/play rosbag
```bash
roslaunch jsk_panda_startup dual_panda1_record.launch # Or roslaunch jsk_panda_startup dual_panda2_record.launch
Expand Down
8 changes: 4 additions & 4 deletions jsk_panda_robot/panda_eus/models/dual_panda.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -109,17 +109,17 @@
<link name="$(arg arm_id_1)_end_effector" >
</link>
<joint name="$(arg arm_id_1)_end_effector_joint" type="fixed">
<parent link="$(arg arm_id_1)_link7"/>
<parent link="$(arg arm_id_1)_hand_tcp"/>
<child link="$(arg arm_id_1)_end_effector"/>
<origin xyz="0 0 0.2" rpy="0 -1.570796327 -0.785398163"/>
<origin xyz="0 0 0" rpy="0 -1.570796327 0"/>
</joint>

<link name="$(arg arm_id_2)_end_effector" >
</link>
<joint name="$(arg arm_id_2)_end_effector_joint" type="fixed">
<parent link="$(arg arm_id_2)_link7"/>
<parent link="$(arg arm_id_2)_hand_tcp"/>
<child link="$(arg arm_id_2)_end_effector"/>
<origin xyz="0 0 0.2" rpy="0 -1.570796327 -0.785398163"/>
<origin xyz="0 0 0" rpy="0 -1.570796327 0"/>
</joint>

</robot>
12 changes: 6 additions & 6 deletions jsk_panda_robot/panda_eus/models/dual_panda.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -20,13 +20,13 @@ larm:
# - pan_tilt_JOINT1 : head-neck-p

rarm-end-coords:
parent: rarm_link7
translate: [0, 0, 0.2]
rotate : [-0.35740972270209, -0.86285515644477, -0.35740630816298, 98.42112728719206]
parent: rarm_hand_tcp
translate: [0, 0, 0]
rotate : [0, -1, 0, 90]
larm-end-coords:
parent: larm_link7
translate: [0, 0, 0.2]
rotate : [-0.35740972270209, -0.86285515644477, -0.35740630816298, 98.42112728719206]
parent: larm_hand_tcp
translate: [0, 0, 0]
rotate : [0, -1, 0, 90]

angle-vector:
reset-pose: [ 0.0, 15.0, 0.0, -135.0, 0.0, 150.0, 45.0,
Expand Down
6 changes: 3 additions & 3 deletions jsk_panda_robot/panda_eus/models/panda.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,9 @@ rarm:
- panda_joint7 : rarm-wrist-y

rarm-end-coords:
parent: panda_link8
translate: [0, 0, 0.1]
rotate : [-0.35740972270209, -0.86285515644477, -0.35740630816298, 98.42112728719206]
parent: panda_hand_tcp
translate: [0, 0, 0]
rotate : [0, -1, 0, 90]

angle-vector:
reset-pose: [ 0.0, -45.0, 0.0, -135.0, 0.0, 90.0, 45.0,
Expand Down