diff --git a/jsk_panda_robot/README.md b/jsk_panda_robot/README.md index eb353bde2b..d035983bce 100644 --- a/jsk_panda_robot/README.md +++ b/jsk_panda_robot/README.md @@ -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 diff --git a/jsk_panda_robot/panda_eus/models/dual_panda.urdf.xacro b/jsk_panda_robot/panda_eus/models/dual_panda.urdf.xacro index d786546287..f47eb6c525 100644 --- a/jsk_panda_robot/panda_eus/models/dual_panda.urdf.xacro +++ b/jsk_panda_robot/panda_eus/models/dual_panda.urdf.xacro @@ -109,17 +109,17 @@ - + - + - + - + diff --git a/jsk_panda_robot/panda_eus/models/dual_panda.yaml b/jsk_panda_robot/panda_eus/models/dual_panda.yaml index 338af0958f..351154873a 100644 --- a/jsk_panda_robot/panda_eus/models/dual_panda.yaml +++ b/jsk_panda_robot/panda_eus/models/dual_panda.yaml @@ -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, diff --git a/jsk_panda_robot/panda_eus/models/panda.yaml b/jsk_panda_robot/panda_eus/models/panda.yaml index 03d3457795..08b55ee3f2 100644 --- a/jsk_panda_robot/panda_eus/models/panda.yaml +++ b/jsk_panda_robot/panda_eus/models/panda.yaml @@ -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,