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

[WIP] auto-stabilizer for jaxon wheel #607

Draft
wants to merge 96 commits into
base: master
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
96 commits
Select commit Hold shift + click to select a range
ab2048a
add param for auto-stabilizer
YutaKojio Apr 27, 2018
248616a
add chidori local-diff
YutaKojio May 25, 2018
e818806
add chidori autost param
YutaKojio May 25, 2018
1ddeba5
modify move_base_gain
YutaKojio May 30, 2018
ebd0af5
suport modify footstep timing
YutaKojio Jul 11, 2018
7324224
chiodri diff
YutaKojio Jul 11, 2018
9e88126
truncate zmp in hrpsys
YutaKojio Jul 16, 2018
830bd83
update
YutaKojio Oct 2, 2018
5f97363
update
YutaKojio Oct 3, 2018
b106576
support leptrino
YutaKojio Dec 12, 2018
8ec3a9d
update
YutaKojio Dec 19, 2018
e4fce3b
update
YutaKojio Dec 24, 2018
9f217d8
update
YutaKojio Jan 26, 2019
ae40da2
set swingEEmodification param
YutaKojio Jan 30, 2019
844f032
change st gain param
YutaKojio Jan 30, 2019
563df01
update
YutaKojio Jan 31, 2019
004e614
rm waist collision pair
YutaKojio Jan 31, 2019
73ec5a2
up
YutaKojio Feb 8, 2019
683c197
up
YutaKojio Apr 25, 2019
413783c
up
YutaKojio Apr 25, 2019
abd4e3b
up
YutaKojio May 17, 2019
80f80b3
up
YutaKojio Jul 14, 2019
702fc4f
up
YutaKojio Aug 24, 2019
02c2e00
up
YutaKojio Nov 29, 2019
3488b12
add fullbody for jaxon
YutaKojio Jan 9, 2020
f85fe3a
overwritable_footstep_index_offset=1
YutaKojio Jan 9, 2020
0e59650
up
YutaKojio Feb 27, 2020
5c67dd6
up
YutaKojio Feb 28, 2020
4f12043
up
YutaKojio Feb 28, 2020
21c43d2
[hrpsys_gazebo_tutorials] enable HRP3HAND simulation
Naoki-Hiraoka May 14, 2020
0f650bf
remove st setting for JAXON
YutaKojio Jun 2, 2020
eed6c70
set optional_go_pos_finalize_footstep_num=1
YutaKojio Jun 5, 2020
e499ddb
Merge branch 'master' into enable-hrp3hand
Naoki-Hiraoka Oct 29, 2020
3575760
Merge remote-tracking branch 'hiraoka/enable-hrp3hand' into work
Naoki-Hiraoka Oct 29, 2020
fbdc213
[hrpsys_ros_bridge_tutorials] fix hand_force_calib_offset_HRP2JSKNT* …
Naoki-Hiraoka Oct 30, 2020
1269ce1
Merge branch 'fix-hand_force_calib_offset' into work
Naoki-Hiraoka Oct 30, 2020
5577659
[hrpsys_ros_bridge_tutorials] add torque gain to servo gain file of J…
kindsenior Oct 31, 2016
4e9172e
[hrpsys_ros_bridge_tutorials] add torque control setting for JAXON_RED
YutaKojio Nov 8, 2020
b1ab989
add new line
YutaKojio Nov 11, 2020
b13257a
add swing phase pdgains
YutaKojio Nov 11, 2020
d4f23c6
up
YutaKojio Nov 11, 2020
968528d
up
Nov 12, 2020
305b965
up
Nov 12, 2020
7cc0d5f
use eefmqp
Nov 29, 2020
9f1e3fb
Merge branch 'hrp2jsknts-move-base' of github.com:Naoki-Hiraoka/rtmro…
YutaKojio Nov 29, 2020
b3faf93
rm st rtc for hrp2
YutaKojio Nov 30, 2020
4c1cdc3
set hrp2 astp param
YutaKojio Nov 30, 2020
704616b
fix param for jaxonred jikki
Nov 30, 2020
4ae7a7c
Merge branch 'auto-stabilizer' of https://github.com/YutaKojio/rtmros…
Nov 30, 2020
e42b0a6
up
Nov 30, 2020
bceaf93
add torque gain
YutaKojio Nov 30, 2020
48b0312
add hrp2 param
YutaKojio Nov 30, 2020
252c9ea
up
YutaKojio Nov 30, 2020
431648f
up
YutaKojio Dec 1, 2020
403458e
add hrp2006 param
YutaKojio Dec 1, 2020
2220b60
add hrp2017 param
YutaKojio Dec 1, 2020
3e60612
up
YutaKojio Dec 1, 2020
f930bc9
up
YutaKojio Dec 1, 2020
bd3a9a4
up
YutaKojio Dec 1, 2020
f17c6be
up
YutaKojio Dec 1, 2020
57d0bec
up
YutaKojio Dec 2, 2020
bd81826
up
YutaKojio Dec 2, 2020
c739a25
fix typo
Naoki-Hiraoka Dec 2, 2020
9067d7b
Merge pull request #1 from Naoki-Hiraoka/auto-stabilizer
YutaKojio Dec 2, 2020
2f6e6e2
up
YutaKojio Dec 2, 2020
92e1714
up
Dec 5, 2020
2349d60
up
Naoki-Hiraoka Dec 5, 2020
10e5670
Merge pull request #3 from Naoki-Hiraoka/auto-stabilizer
YutaKojio Dec 5, 2020
c255741
remove octd rfu
Naoki-Hiraoka Dec 5, 2020
5b21c1f
Merge pull request #4 from Naoki-Hiraoka/auto-stabilizer
YutaKojio Dec 5, 2020
e1e2782
[hrp2_hrpsys_config] fix st/abc parameter for real robot
Naoki-Hiraoka Dec 7, 2020
1428784
[HRP2JSK*] add reset-manip-walk-pose
Naoki-Hiraoka Dec 7, 2020
2a69bba
Merge pull request #6 from Naoki-Hiraoka/reset-manip-walk-pose
YutaKojio Dec 7, 2020
03ac764
Merge pull request #5 from Naoki-Hiraoka/auto-stabilizer
YutaKojio Dec 7, 2020
cb65d9e
up
Dec 18, 2020
3695706
up
Apr 2, 2021
72a48a4
set default value of retrieve duration
ketaro-m Jun 22, 2021
99525c9
Merge pull request #7 from ketaro-m/pr-add-retrieve-duration
YutaKojio Jun 22, 2021
a8dfc50
[hrpsys_ros_bridge_tutorials][JAXON_RED] replace foot with Leptrino f…
kirohy Jun 21, 2021
5cd85b0
[hrpsys_ros_bridge_tutorials][JAXON] replace foot with KAWADA
kirohy Jun 21, 2021
7a23d48
up
YutaKojio Jul 4, 2021
763a6c6
up
YutaKojio Jul 16, 2021
bb6f3c6
Merge branch 'auto-stabilizer' of https://github.com/YutaKojio/rtmros…
jaxon-user Jul 16, 2021
3dd5fb8
merge master
YutaKojio Jul 17, 2021
9cfda20
rm sernsorRPY_offset
YutaKojio Jul 18, 2021
30a5742
up
YutaKojio Nov 11, 2021
2fba470
up
YutaKojio Nov 17, 2021
6400605
disable rot spring gain
YutaKojio Nov 17, 2021
696a870
up
YutaKojio Nov 19, 2021
7a805c1
up
YutaKojio Dec 4, 2021
c1bc9f9
up
YutaKojio Jan 2, 2022
cae7c99
up
YutaKojio Feb 13, 2022
16cef35
add jaxon_blue
YutaKojio Feb 15, 2022
ad44726
up
YutaKojio Feb 15, 2022
ba5f3ec
up
YutaKojio Feb 23, 2022
be05180
use torque mode
YutaKojio Mar 31, 2022
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
26 changes: 1 addition & 25 deletions hrpsys_gazebo_tutorials/config/HRP2JSKNT.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ hrpsys_gazebo_configuration:
### name of robot (using for namespace)
robotname: HRP2JSKNT
### joint_id (order) conversion from gazebo to hrpsys, joint_id_list[gazebo_id] := hrpsys_id
joint_id_list: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45]
joint_id_list: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33]
### joints : list used in gazebo, sizeof(joint_id_list) == sizeof(joints)
joints:
- RLEG_JOINT0
Expand Down Expand Up @@ -48,18 +48,6 @@ hrpsys_gazebo_configuration:
- LARM_JOINT5
- LARM_JOINT6
- LARM_JOINT7
- L_THUMBCM_Y
- L_THUMBCM_P
- L_INDEXMP_R
- L_INDEXMP_P
- L_INDEXPIP_R
- L_MIDDLEPIP_R
- R_THUMBCM_Y
- R_THUMBCM_P
- R_INDEXMP_R
- R_INDEXMP_P
- R_INDEXPIP_R
- R_MIDDLEPIP_R
## jointid:
gains:
CHEST_JOINT0: {p: 2800.0, d: 3.0, i: 0.0, i_clamp: 0.0, p_v: 350.0}
Expand Down Expand Up @@ -94,18 +82,6 @@ hrpsys_gazebo_configuration:
RLEG_JOINT4: {p: 1400.0, d: 1.5, i: 0.0, i_clamp: 0.0, p_v: 350.0}
RLEG_JOINT5: {p: 3500.0, d: 3.0, i: 0.0, i_clamp: 0.0, p_v: 350.0}
RLEG_JOINT6: {p: 120.0, d: 0.013, i: 0.0, i_clamp: 0.0, p_v: 250.0}
L_INDEXMP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
L_INDEXMP_P: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
L_INDEXPIP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
L_MIDDLEPIP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
L_THUMBCM_Y: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
L_THUMBCM_P: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
R_INDEXMP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
R_INDEXMP_P: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
R_INDEXPIP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
R_MIDDLEPIP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
R_THUMBCM_Y: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
R_THUMBCM_P: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}

force_torque_sensors:
- rfsensor
Expand Down
26 changes: 1 addition & 25 deletions hrpsys_gazebo_tutorials/config/HRP2JSKNTS.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ hrpsys_gazebo_configuration:
### name of robot (using for namespace)
robotname: HRP2JSKNTS
### joint_id (order) conversion from gazebo to hrpsys, joint_id_list[gazebo_id] := hrpsys_id
joint_id_list: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45]
joint_id_list: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33]
### joints : list used in gazebo, sizeof(joint_id_list) == sizeof(joints)
joints:
- RLEG_JOINT0
Expand Down Expand Up @@ -48,18 +48,6 @@ hrpsys_gazebo_configuration:
- LARM_JOINT5
- LARM_JOINT6
- LARM_JOINT7
- L_THUMBCM_Y
- L_THUMBCM_P
- L_INDEXMP_R
- L_INDEXMP_P
- L_INDEXPIP_R
- L_MIDDLEPIP_R
- R_THUMBCM_Y
- R_THUMBCM_P
- R_INDEXMP_R
- R_INDEXMP_P
- R_INDEXPIP_R
- R_MIDDLEPIP_R
## jointid:
gains:
CHEST_JOINT0: {p: 2800.0, d: 3.0, i: 0.0, i_clamp: 0.0, p_v: 350.0}
Expand Down Expand Up @@ -94,18 +82,6 @@ hrpsys_gazebo_configuration:
RLEG_JOINT4: {p: 1400.0, d: 1.5, i: 0.0, i_clamp: 0.0, p_v: 350.0}
RLEG_JOINT5: {p: 3500.0, d: 3.0, i: 0.0, i_clamp: 0.0, p_v: 350.0}
RLEG_JOINT6: {p: 120.0, d: 0.013, i: 0.0, i_clamp: 0.0, p_v: 250.0}
L_INDEXMP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
L_INDEXMP_P: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
L_INDEXPIP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
L_MIDDLEPIP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
L_THUMBCM_Y: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
L_THUMBCM_P: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
R_INDEXMP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
R_INDEXMP_P: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
R_INDEXPIP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
R_MIDDLEPIP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
R_THUMBCM_Y: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
R_THUMBCM_P: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}

force_torque_sensors:
- rfsensor
Expand Down
42 changes: 42 additions & 0 deletions hrpsys_gazebo_tutorials/config/HRP3HAND.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
hrp3hand_hrpsys_gazebo_configuration:
### velocity feedback for joint control, use parameter gains/joint_name/p_v
use_velocity_feedback: false
use_joint_effort: true
iob_rate: 100
### loose synchronization default true
use_loose_synchronized: false
### synchronized hrpsys and gazebo
# use_synchronized_command: false
# iob_substeps: 5
### name of robot (using for namespace)
robotname: HRP3HAND
### joint_id (order) conversion from gazebo to hrpsys, joint_id_list[gazebo_id] := hrpsys_id
joint_id_list: [ 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11]
### joints : list used in gazebo, sizeof(joint_id_list) == sizeof(joints)
joints:
- R_THUMBCM_Y
- R_THUMBCM_P
- R_INDEXMP_R
- R_INDEXMP_P
- R_INDEXPIP_R
- R_MIDDLEPIP_R
- L_THUMBCM_Y
- L_THUMBCM_P
- L_INDEXMP_R
- L_INDEXMP_P
- L_INDEXPIP_R
- L_MIDDLEPIP_R
## jointid:
gains:
R_INDEXMP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
R_INDEXMP_P: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
R_INDEXPIP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
R_MIDDLEPIP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
R_THUMBCM_Y: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
R_THUMBCM_P: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
L_INDEXMP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
L_INDEXMP_P: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
L_INDEXPIP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
L_MIDDLEPIP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
L_THUMBCM_Y: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
L_THUMBCM_P: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0}
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,7 @@
<arg name="SYNCHRONIZED" default="false" />

<rosparam command="load"
file="$(find hrpsys_gazebo_tutorials)/config/HRP3HAND_L.yaml" ns="HRP3HAND_L" />
<rosparam command="load"
file="$(find hrpsys_gazebo_tutorials)/config/HRP3HAND_R.yaml" ns="HRP3HAND_R" />
file="$(find hrpsys_gazebo_tutorials)/config/HRP3HAND.yaml" ns="HRP3HAND" />

<include file="$(find hrpsys_gazebo_general)/launch/gazebo_robot_no_controllers.launch">
<arg name="ROBOT_TYPE" value="HRP2JSKNT" />
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,7 @@
<arg name="SYNCHRONIZED" default="false" />

<rosparam command="load"
file="$(find hrpsys_gazebo_tutorials)/config/HRP3HAND_L.yaml" ns="HRP3HAND_L" />
<rosparam command="load"
file="$(find hrpsys_gazebo_tutorials)/config/HRP3HAND_R.yaml" ns="HRP3HAND_R" />
file="$(find hrpsys_gazebo_tutorials)/config/HRP3HAND.yaml" ns="HRP3HAND" />

<include file="$(find hrpsys_gazebo_general)/launch/gazebo_robot_no_controllers.launch">
<arg name="ROBOT_TYPE" value="HRP2JSKNTS" />
Expand Down
23 changes: 23 additions & 0 deletions hrpsys_gazebo_tutorials/launch/hrp2jsknt_hrpsys_bringup.launch
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,11 @@
<!-- <rosparam command="load" -->
<!-- file="$(find hrpsys_ros_bridge_tutorials)/models/HRP2JSKNT_controller_config.yaml" /> -->

<!-- HRP3HAND parameters -->
<env name="HC_IOB_HRPSYS_GAZEBO_IOB_NAME" value="hrp3hand_hrpsys_gazebo_iob" />
<env name="HC_IOB_HRPSYS_GAZEBO_ROBOTNAME" value="HRP3HAND" />
<env name="HC_IOB_HRPSYS_GAZEBO_CONFIGURATION" value="hrp3hand_hrpsys_gazebo_configuration" />

<include file="$(find hrpsys_gazebo_general)/launch/robot_hrpsys_bringup.launch">
<arg name="ROBOT_TYPE" value="HRP2JSKNT" />
<arg name="CONF_DIR" value="$(find hrpsys_ros_bridge_tutorials)/models" />
Expand All @@ -23,5 +28,23 @@
<arg name="HRPSYS_PY_NAME" default="hrp2jsknt_hrpsys_config.py"/>
<arg name="KINEMATICS_MODE" value="$(arg KINEMATICS_MODE)"/>
<arg name="HRPSYS_RATE" value="250" />
<arg name="HRPSYS_ADDITIONAL_LOAD_PATH" value="$(find jsk_hrp2_ros_bridge)/lib/gazebo"/> <!-- HRP3HANDController -->
<arg name="HRPSYS_OPT_RTC_CONFIG_ARGS" default='-o "example.HRP3HandController.config_file:$(find hrpsys_ros_bridge_tutorials)/models/HRP2JSKNT.conf"'/> <!-- HRP3HANDController -->
</include>

<!-- HRP3HANDControllerServiceROSBridge -->
<env name="LANG" value="C" />
<env name="ORBgiopMaxMsgSize" value="2147483648" />
<arg name="nameserver" default="localhost" />
<arg name="corbaport" default="15005" />
<arg name="managerport" default="2810" />
<env name="RTCTREE_NAMESERVERS" value="$(arg nameserver):$(arg corbaport)" />
<env name="RTC_CONNECTION_CHECK_ONCE" value="true" />

<node pkg="jsk_hrp2_ros_bridge" name="HRP3HandControllerServiceROSBridge" type="HRP3HandControllerServiceROSBridgeComp"
output="screen" args='-o "corba.master_manager:$(arg nameserver):$(arg managerport)" -o "corba.nameservers:$(arg nameserver):$(arg corbaport)" -o "naming.formats:%n.rtc" -o "exec_cxt.periodic.type:PeriodicExecutionContext" -o "exec_cxt.periodic.rate:2000" -o "logger.file_name:/tmp/rtc%p.log"' />
<rtconnect from="HRP3HandControllerServiceROSBridge.rtc:HRP3HandControllerService" to="hc.rtc:HRP3HandControllerService" subscription_type="new"/>
<rtactivate component="HRP3HandControllerServiceROSBridge.rtc" />
<node name="rtmlaunch_hrp2jsknt_hrpsys_bridgup" pkg="openrtm_tools" type="rtmlaunch.py" args="$(find hrpsys_gazebo_tutorials)/launch/hrp2jsknt_hrpsys_bringup.launch" output="screen"/>

</launch>
23 changes: 23 additions & 0 deletions hrpsys_gazebo_tutorials/launch/hrp2jsknts_hrpsys_bringup.launch
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,11 @@
<!-- <rosparam command="load" -->
<!-- file="$(find hrpsys_ros_bridge_tutorials)/models/HRP2JSKNTS_controller_config.yaml" /> -->

<!-- HRP3HAND parameters -->
<env name="HC_IOB_HRPSYS_GAZEBO_IOB_NAME" value="hrp3hand_hrpsys_gazebo_iob" />
<env name="HC_IOB_HRPSYS_GAZEBO_ROBOTNAME" value="HRP3HAND" />
<env name="HC_IOB_HRPSYS_GAZEBO_CONFIGURATION" value="hrp3hand_hrpsys_gazebo_configuration" />

<include file="$(find hrpsys_gazebo_general)/launch/robot_hrpsys_bringup.launch">
<arg name="ROBOT_TYPE" value="HRP2JSKNTS" />
<arg name="CONF_DIR" value="$(find hrpsys_ros_bridge_tutorials)/models" />
Expand All @@ -24,5 +29,23 @@
<arg name="HRPSYS_PY_NAME" default="hrp2jsknts_hrpsys_config.py"/>
<arg name="KINEMATICS_MODE" value="$(arg KINEMATICS_MODE)"/>
<arg name="HRPSYS_RATE" value="250" />
<arg name="HRPSYS_ADDITIONAL_LOAD_PATH" value="$(find jsk_hrp2_ros_bridge)/lib/gazebo"/> <!-- HRP3HANDController -->
<arg name="HRPSYS_OPT_RTC_CONFIG_ARGS" default='-o "example.HRP3HandController.config_file:$(find hrpsys_ros_bridge_tutorials)/models/HRP2JSKNTS.conf"'/> <!-- HRP3HANDController -->
</include>

<!-- HRP3HANDControllerServiceROSBridge -->
<env name="LANG" value="C" />
<env name="ORBgiopMaxMsgSize" value="2147483648" />
<arg name="nameserver" default="localhost" />
<arg name="corbaport" default="15005" />
<arg name="managerport" default="2810" />
<env name="RTCTREE_NAMESERVERS" value="$(arg nameserver):$(arg corbaport)" />
<env name="RTC_CONNECTION_CHECK_ONCE" value="true" />

<node pkg="jsk_hrp2_ros_bridge" name="HRP3HandControllerServiceROSBridge" type="HRP3HandControllerServiceROSBridgeComp"
output="screen" args='-o "corba.master_manager:$(arg nameserver):$(arg managerport)" -o "corba.nameservers:$(arg nameserver):$(arg corbaport)" -o "naming.formats:%n.rtc" -o "exec_cxt.periodic.type:PeriodicExecutionContext" -o "exec_cxt.periodic.rate:2000" -o "logger.file_name:/tmp/rtc%p.log"' />
<rtconnect from="HRP3HandControllerServiceROSBridge.rtc:HRP3HandControllerService" to="hc.rtc:HRP3HandControllerService" subscription_type="new"/>
<rtactivate component="HRP3HandControllerServiceROSBridge.rtc" />
<node name="rtmlaunch_hrp2jsknts_hrpsys_bridgup" pkg="openrtm_tools" type="rtmlaunch.py" args="$(find hrpsys_gazebo_tutorials)/launch/hrp2jsknts_hrpsys_bringup.launch" output="screen"/>

</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,12 @@
<controller>hrpsys_gazebo_configuration</controller>
</plugin>
</gazebo>
<gazebo>
<plugin filename="libIOBPlugin.so" name="hrp3hand_hrpsys_gazebo_plugin">
<robotname>HRP3HAND</robotname>
<controller>hrp3hand_hrpsys_gazebo_configuration</controller>
</plugin>
</gazebo>
<!-- add imu sensor -->
<gazebo reference="CHEST_LINK1">
<sensor name="waist_imu" type="imu">
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,12 @@
<controller>hrpsys_gazebo_configuration</controller>
</plugin>
</gazebo>
<gazebo>
<plugin filename="libIOBPlugin.so" name="hrp3hand_hrpsys_gazebo_plugin">
<robotname>HRP3HAND</robotname>
<controller>hrp3hand_hrpsys_gazebo_configuration</controller>
</plugin>
</gazebo>
<!-- add imu sensor -->
<gazebo reference="CHEST_LINK1">
<sensor name="waist_imu" type="imu">
Expand Down
4 changes: 2 additions & 2 deletions hrpsys_ros_bridge_tutorials/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -223,7 +223,7 @@ compile_openhrp_model_for_closed_robots(HRP2W HRP2W_for_OpenHRP3 HRP2W
--simulation-timestep-option "0.004"
--simulation-joint-properties-option "RARM_JOINT3.angle,-1.5708,LARM_JOINT3.angle,-1.5708"
)
gen_minmax_table_for_closed_robots(HRP2W HRP2W_for_OpenHRP3 HRP2W)
# gen_minmax_table_for_closed_robots(HRP2W HRP2W_for_OpenHRP3 HRP2W)
compile_openhrp_model_for_closed_robots(HRP2G HRP2G_for_OpenHRP3 HRP2G
--conf-file-option "end_effectors: rarm,RARM_JOINT6,CHEST_JOINT1,0.0,0.0169,-0.174,0.0,1.0,0.0,1.5708, larm,LARM_JOINT6,CHEST_JOINT1,0.0,-0.0169,-0.174,0.0,1.0,0.0,1.5708"
--conf-file-option "# for ThermoEstimator"
Expand Down Expand Up @@ -426,7 +426,7 @@ compile_rbrain_model_for_closed_robots(CHIDORI CHIDORI CHIDORI
--conf-dt-option "0.002"
--simulation-timestep-option "0.002"
--conf-file-option "collision_loop: 20"
--conf-file-option "collision_pair: WAIST:LLEG_JOINT2 WAIST:RLEG_JOINT2 LLEG_JOINT2:LLEG_JOINT5 LLEG_JOINT2:RLEG_JOINT2 LLEG_JOINT2:RLEG_JOINT3 LLEG_JOINT2:RLEG_JOINT5 LLEG_JOINT3:RLEG_JOINT2 LLEG_JOINT3:RLEG_JOINT3 LLEG_JOINT3:RLEG_JOINT5 LLEG_JOINT5:RLEG_JOINT2 LLEG_JOINT5:RLEG_JOINT3 LLEG_JOINT5:RLEG_JOINT5 RLEG_JOINT2:RLEG_JOINT5"
--conf-file-option "collision_pair: LLEG_JOINT2:LLEG_JOINT5 LLEG_JOINT2:RLEG_JOINT2 LLEG_JOINT2:RLEG_JOINT3 LLEG_JOINT2:RLEG_JOINT5 LLEG_JOINT3:RLEG_JOINT2 LLEG_JOINT3:RLEG_JOINT3 LLEG_JOINT3:RLEG_JOINT5 LLEG_JOINT5:RLEG_JOINT2 LLEG_JOINT5:RLEG_JOINT3 LLEG_JOINT5:RLEG_JOINT5 RLEG_JOINT2:RLEG_JOINT5"
--conf-file-option "# SequencePlayer optional data (contactStates x 2 + controlSwingTime x 2 (2 is rfsensor, lfsensor)"
--conf-file-option "seq_optional_data_dim: 4"
)
Expand Down
24 changes: 12 additions & 12 deletions hrpsys_ros_bridge_tutorials/models/CHIDORI.PDgains_sim.dat
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
33000 240
83000 240
33000 240
33000 240
47000 240
33000 240
33000 240
83000 240
33000 240
33000 240
47000 240
33000 240
33000 240 1 0
83000 240 1 0
33000 240 1 0
33000 240 1 0
47000 240 1 0
33000 240 1 0
33000 240 1 0
83000 240 1 0
33000 240 1 0
33000 240 1 0
47000 240 1 0
33000 240 1 0
64 changes: 32 additions & 32 deletions hrpsys_ros_bridge_tutorials/models/HRP2JSK.PDgain.dat
Original file line number Diff line number Diff line change
@@ -1,32 +1,32 @@
1800 500
21500 500
8250 500
18450 500
4840 500
3750 500
1800 500
21500 500
8250 500
18450 500
4840 500
3750 500
8000 500
13080 500
1320 100
1320 100
5400 100
5550 100
430 100
8700 100
1400 100
460 100
1870 100
1400 100
5400 100
5550 100
430 100
8700 100
1400 100
460 100
1870 100
1400 100
1800 500 1 0
21500 500 1 0
8250 500 1 0
18450 500 1 0
4840 500 1 0
3750 500 1 0
1800 500 1 0
21500 500 1 0
8250 500 1 0
18450 500 1 0
4840 500 1 0
3750 500 1 0
8000 500 1 0
13080 500 1 0
1320 100 1 0
1320 100 1 0
5400 100 1 0
5550 100 1 0
430 100 1 0
8700 100 1 0
1400 100 1 0
460 100 1 0
1870 100 1 0
1400 100 1 0
5400 100 1 0
5550 100 1 0
430 100 1 0
8700 100 1 0
1400 100 1 0
460 100 1 0
1870 100 1 0
1400 100 1 0
Loading