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] Gazebo hrp2jsknts #562

Open
wants to merge 11 commits into
base: master
Choose a base branch
from
Open
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
11 changes: 10 additions & 1 deletion .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -49,4 +49,13 @@ hrpsys_ros_bridge_tutorials/scripts/*_unstable_hrpsys_config.py

# generated files in hrpsys_tutorials
hrpsys_tutorials/models/*.conf
hrpsys_tutorials/models/*.xml
hrpsys_tutorials/models/*.xml

# generated files in hrpsys_gazebo_tutorials
hrpsys_gazebo_tutorials/config/HRP2JSKNTS.conf
hrpsys_gazebo_tutorials/config/rtcdRobotModeHRP2Common.conf
hrpsys_gazebo_tutorials/launch/hrp2017_auditor_gazebo.launch
hrpsys_gazebo_tutorials/launch/hrp2017_gazebo.launch
hrpsys_gazebo_tutorials/launch/hrp2017_ros_bridge_gazebo.launch
hrpsys_gazebo_tutorials/robot_models/HRP2JSKNTS/HRP2JSKNTS.urdf
hrpsys_gazebo_tutorials/scripts/jsk_hrp2_gazebo_setup.py
37 changes: 36 additions & 1 deletion hrpsys_gazebo_tutorials/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,7 +1,9 @@
cmake_minimum_required(VERSION 2.8.3)
project(hrpsys_gazebo_tutorials)

find_package(catkin REQUIRED COMPONENTS euscollada hrpsys_ros_bridge hrpsys_ros_bridge_tutorials hrpsys_gazebo_general)
find_package(catkin REQUIRED COMPONENTS euscollada hrpsys_ros_bridge hrpsys_ros_bridge_tutorials hrpsys_gazebo_general jsk_hrp2_ros_bridge hrp2_models euscollada xacro)

catkin_python_setup()

set(PKG_CONFIG_PATH ${hrpsys_PREFIX}/lib/pkgconfig:$ENV{PKG_CONFIG_PATH})
find_package(PkgConfig)
Expand All @@ -10,6 +12,8 @@ pkg_check_modules(hrpsys hrpsys-base REQUIRED)
pkg_check_modules(collada_urdf_jsk_patch collada_urdf_jsk_patch)

catkin_package(CATKIN_DEPENDS euscollada hrpsys_ros_bridge hrpsys_ros_bridge_tutorials hrpsys_gazebo_general)

add_subdirectory(rtc)

catkin_add_env_hooks(99.hrpsys_gazebo_tutorials SHELLS bash zsh
DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/env-hooks)
Expand All @@ -18,3 +22,34 @@ catkin_add_env_hooks(99.hrpsys_gazebo_tutorials SHELLS bash zsh
install(DIRECTORY euslisp worlds launch config environment_models DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
PATTERN ".svn" EXCLUDE)
install(DIRECTORY scripts DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} USE_SOURCE_PERMISSIONS)

if (jsk_hrp2_ros_bridge_SOURCE_PREFIX)
set(jsk_hrp2_ros_bridge_PACKAGE_PATH ${jsk_hrp2_ros_bridge_SOURCE_PREFIX})
endif()
if (hrp2_models_SOURCE_PREFIX)
set(hrp2_models_PACKAGE_PATH ${hrp2_models_SOURCE_PREFIX})
endif()
if (hrpsys_gazebo_general_SOURCE_PREFIX)
set(hrpsys_gazebo_general_PACKAGE_PATH ${hrpsys_gazebo_general_SOURCE_PREFIX})
endif()

execute_process(COMMAND sed -e "s#@MODULE_LOAD_PATH@#${PROJECT_SOURCE_DIR}/lib,${hrpsys_gazebo_general_PACKAGE_PATH}/lib,${hrpsys_PREFIX}/lib#g" "${jsk_hrp2_ros_bridge_PACKAGE_PATH}/config/rtcdRobotModeHRP2Common.conf.in"
OUTPUT_FILE ${PROJECT_SOURCE_DIR}/config/rtcdRobotModeHRP2Common.conf)

execute_process(COMMAND sed -e "s#^model:.*$#model: ${hrp2_models_PACKAGE_PATH}/HRP2JSKNTS_for_OpenHRP3/HRP2JSKNTSmain.wrl#g" -e "s#^pdgains.file_name:.*$#pdgains.file_name: ${jsk_hrp2_ros_bridge_PACKAGE_PATH}/iob/PDgainsHRP2JSKNTS.sav#g" "${jsk_hrp2_ros_bridge_PACKAGE_PATH}/config/HRP2JSKNTS.conf"
OUTPUT_FILE ${PROJECT_SOURCE_DIR}/config/HRP2JSKNTS.conf)

execute_process(COMMAND sed -e "s#/home/grxuser/prog/rtmros_hrp2/jsk_hrp2_ros_bridge/force_sensor_calib_data/hand-calib_HRP2JSKNTS_[0-9]\\+#${PROJECT_SOURCE_DIR}/config/hand-calib_HRP2JSKNTS#g" -e "s#/home/grxuser/prog/rtmros_hrp2/jsk_hrp2_ros_bridge#${PROJECT_SOURCE_DIR}#g" -e "s#/home/grxuser/prog/rtmros_hrp2/hrp2_models#${hrp2_models_PACKAGE_PATH}#g" "${jsk_hrp2_ros_bridge_PACKAGE_PATH}/scripts/jsk_hrp2_setup.py"
OUTPUT_FILE ${PROJECT_SOURCE_DIR}/scripts/jsk_hrp2_gazebo_setup.py)

execute_process(COMMAND "${PROJECT_SOURCE_DIR}/scripts/replace_xmls.py" "${jsk_hrp2_ros_bridge_PACKAGE_PATH}/launch/hrp2017.launch" -C "${PROJECT_SOURCE_DIR}/config/hrp2017_gazebo.yaml"
OUTPUT_FILE ${PROJECT_SOURCE_DIR}/launch/hrp2017_gazebo.launch)

execute_process(COMMAND "${PROJECT_SOURCE_DIR}/scripts/replace_xmls.py" "${jsk_hrp2_ros_bridge_PACKAGE_PATH}/launch/hrp2017_ros_bridge.launch" -C "${PROJECT_SOURCE_DIR}/config/hrp2017_ros_bridge_gazebo.yaml"
OUTPUT_FILE ${PROJECT_SOURCE_DIR}/launch/hrp2017_ros_bridge_gazebo.launch)

execute_process(COMMAND "${PROJECT_SOURCE_DIR}/scripts/replace_xmls.py" "${jsk_hrp2_ros_bridge_PACKAGE_PATH}/launch/hrp2017_auditor.launch" -C "${PROJECT_SOURCE_DIR}/config/hrp2017_auditor_gazebo.yaml"
OUTPUT_FILE ${PROJECT_SOURCE_DIR}/launch/hrp2017_auditor_gazebo.launch)

execute_process(COMMAND "${xacro_PREFIX}/lib/xacro/xacro" "${PROJECT_SOURCE_DIR}/robot_models/HRP2JSKNTS/HRP2JSKNTS.urdf.xacro"
OUTPUT_FILE ${PROJECT_SOURCE_DIR}/robot_models/HRP2JSKNTS/HRP2JSKNTS.urdf)
98 changes: 39 additions & 59 deletions hrpsys_gazebo_tutorials/config/HRP2JSKNTS.yaml
Original file line number Diff line number Diff line change
@@ -1,7 +1,9 @@
hrpsys_gazebo_configuration:
### velocity feedback for joint control, use parameter gains/joint_name/p_v
use_velocity_feedback: true
use_joint_effort: true
use_velocity_feedback: false
use_joint_effort: false
use_pd_feedback: true
use_servo_on: true
iob_rate: 250
### loose synchronization default true
# use_loose_synchronized: false
Expand All @@ -11,7 +13,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,64 +50,42 @@ 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: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 250.0}
CHEST_JOINT1: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 250.0}
HEAD_JOINT0: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0}
HEAD_JOINT1: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0}
LARM_JOINT0: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0}
LARM_JOINT1: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0}
LARM_JOINT2: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0}
LARM_JOINT3: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0}
LARM_JOINT4: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0}
LARM_JOINT5: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0}
LARM_JOINT6: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0}
RARM_JOINT0: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0}
RARM_JOINT1: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0}
RARM_JOINT2: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0}
RARM_JOINT3: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0}
RARM_JOINT4: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0}
RARM_JOINT5: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0}
RARM_JOINT6: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0}
LLEG_JOINT0: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 250.0} # CRTOCH-Y
LLEG_JOINT1: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 350.0} # CRTOCH-R
LLEG_JOINT2: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 325.0} # CRTOCH-P
LLEG_JOINT3: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 450.0} # KNEE-P
LLEG_JOINT4: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 350.0} # ANKLE-P
LLEG_JOINT5: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 350.0} # ANKLE-R
LLEG_JOINT6: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 250.0} # TOE-R
RLEG_JOINT0: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 250.0}
RLEG_JOINT1: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 350.0}
RLEG_JOINT2: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 325.0}
RLEG_JOINT3: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 450.0}
RLEG_JOINT4: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 350.0}
RLEG_JOINT5: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 350.0}
RLEG_JOINT6: {p: 700.0, d: 0.075, 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}
CHEST_JOINT0: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 250.0, vp: 0.0}
CHEST_JOINT1: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 250.0, vp: 0.0}
HEAD_JOINT0: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0, vp: 0.0}
HEAD_JOINT1: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0, vp: 0.0}
LARM_JOINT0: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0, vp: 0.0}
LARM_JOINT1: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0, vp: 0.0}
LARM_JOINT2: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0, vp: 0.0}
LARM_JOINT3: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0, vp: 0.0}
LARM_JOINT4: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0, vp: 0.0}
LARM_JOINT5: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0, vp: 0.0}
LARM_JOINT6: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0, vp: 0.0}
LARM_JOINT7: {p: 0.0, d: 0.0, i: 0.0, i_clamp: 0.0, p_v: 0.0, vp: 0.0}
RARM_JOINT0: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0, vp: 0.0}
RARM_JOINT1: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0, vp: 0.0}
RARM_JOINT2: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0, vp: 0.0}
RARM_JOINT3: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0, vp: 0.0}
RARM_JOINT4: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0, vp: 0.0}
RARM_JOINT5: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0, vp: 0.0}
RARM_JOINT6: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 150.0, vp: 0.0}
RARM_JOINT7: {p: 0.0, d: 0.0, i: 0.0, i_clamp: 0.0, p_v: 0.0, vp: 0.0}
LLEG_JOINT0: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 250.0, vp: 0.0} # CRTOCH-Y
LLEG_JOINT1: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 350.0, vp: 0.0} # CRTOCH-R
LLEG_JOINT2: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 325.0, vp: 0.0} # CRTOCH-P
LLEG_JOINT3: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 450.0, vp: 0.0} # KNEE-P
LLEG_JOINT4: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 350.0, vp: 0.0} # ANKLE-P
LLEG_JOINT5: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 350.0, vp: 0.0} # ANKLE-R
LLEG_JOINT6: {p: 120.0, d: 0.013, i: 0.0, i_clamp: 0.0, p_v: 250.0, vp: 0.0} # TOE-R
RLEG_JOINT0: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 250.0, vp: 0.0}
RLEG_JOINT1: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 350.0, vp: 0.0}
RLEG_JOINT2: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 325.0, vp: 0.0}
RLEG_JOINT3: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 450.0, vp: 0.0}
RLEG_JOINT4: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 350.0, vp: 0.0}
RLEG_JOINT5: {p: 700.0, d: 0.075, i: 0.0, i_clamp: 0.0, p_v: 350.0, vp: 0.0}
RLEG_JOINT6: {p: 120.0, d: 0.013, i: 0.0, i_clamp: 0.0, p_v: 250.0, vp: 0.0}

force_torque_sensors:
- rfsensor
Expand Down
44 changes: 44 additions & 0 deletions hrpsys_gazebo_tutorials/config/HRP3HAND.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
hrp3hand_hrpsys_gazebo_configuration:
### velocity feedback for joint control, use parameter gains/joint_name/p_v
use_velocity_feedback: false
use_joint_effort: false
use_pd_feedback: true
use_servo_on: true
iob_rate: 250
### 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: [ 6, 7, 8, 9, 10, 11, 0, 1, 2, 3, 4, 5]
### joints : list used in gazebo, sizeof(joint_id_list) == sizeof(joints)
joints:
- 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:
L_INDEXMP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0, vp: 0.0}
L_INDEXMP_P: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0, vp: 0.0}
L_INDEXPIP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0, vp: 0.0}
L_MIDDLEPIP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0, vp: 0.0}
L_THUMBCM_Y: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0, vp: 0.0}
L_THUMBCM_P: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0, vp: 0.0}
R_INDEXMP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0, vp: 0.0}
R_INDEXMP_P: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0, vp: 0.0}
R_INDEXPIP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0, vp: 0.0}
R_MIDDLEPIP_R: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0, vp: 0.0}
R_THUMBCM_Y: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0, vp: 0.0}
R_THUMBCM_P: {p: 10.0, d: 0.01, i: 0.0, i_clamp: 0.0, p_v: 10.0, vp: 0.0}
4 changes: 4 additions & 0 deletions hrpsys_gazebo_tutorials/config/hand-calib_HRP2JSKNTS
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
lfsensor 0 0 0 0 0 0 0 0 0 0
lhsensor 0 0 0 0 0 0 0.00538113 -0.00209447 -0.0248345 1.6618102
rfsensor 0 0 0 0 0 0 0 0 0 0
rhsensor 0 0 0 0 0 0 0.00538113 0.00209447 -0.0248345 1.6618102
7 changes: 7 additions & 0 deletions hrpsys_gazebo_tutorials/config/hrp2017_auditor_gazebo.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
replace_xmls:
- match_rule:
tag: include
attribute:
- name: file
value: '$(find jsk_pcl_ros)/launch/openni2_remote.launch'
replaced_xml: '<include file="$(find openni2_launch)/launch/openni2.launch"> <arg name="publish_tf" value="false" /> <arg name="camera" value="camera_remote" /> <arg name="depth_registration" value="false" /> <arg name="load_driver" value="false" /> <arg name="rgb_processing" value="true" /> <arg name="depth_processing" value="true" /> <arg name="depth_registered_processing" value="true" /> <arg name="rgb_camera_info_url" value="" /> <arg name="depth_camera_info_url" value="" /> </include>'
55 changes: 55 additions & 0 deletions hrpsys_gazebo_tutorials/config/hrp2017_gazebo.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
replace_xmls:
- match_rule:
tag: include
attribute:
- name: file
value: '$(find jsk_hrp2_ros_bridge)/launch/hrp2017_ros_bridge.launch'
replaced_attribute_name: file
replaced_attribute_value: '$(find hrpsys_gazebo_tutorials)/launch/hrp2017_ros_bridge_gazebo.launch'
- match_rule:
tag: arg
attribute:
- name: name
value: NTP_HOSTNAME
parent_tag: include
parent_attribute:
- name: file
value: '$(find jsk_hrp2_ros_bridge)/launch/jsk_robot_common.launch'
replaced_attribute_name: value
replaced_attribute_value: localhost
- match_rule:
tag: node
attribute:
- name: name
value: thermo_publisher
replaced_xml: '<node name="thermo_publisher" pkg="topic_tools" type="relay" args="/HRP2JSKNTS/RLEG_thermo/case thermo_rleg" />'
- match_rule:
tag: node
attribute:
- name: name
value: thermo_publisher2
replaced_xml: '<node name="thermo_publisher2" pkg="topic_tools" type="relay" args="/HRP2JSKNTS/LLEG_thermo/case thermo_lleg" />'
- match_rule:
tag: include
attribute:
- name: file
value: '$(find jsk_pcl_ros)/launch/openni2_local.launch'
replaced_xml: ''
- match_rule:
tag: node
attribute:
- name: pkg
value: dynamic_reconfigure
replaced_xml: ''
- match_rule:
tag: include
attribute:
- name: file
value: '$(find jsk_hrp2_ros_bridge)/launch/chest_camera.launch'
replaced_xml: ''
- match_rule:
tag: include
attribute:
- name: file
value: '$(find voice_text)/launch/voice_text.launch'
replaced_xml: ''
24 changes: 24 additions & 0 deletions hrpsys_gazebo_tutorials/config/hrp2017_ros_bridge_gazebo.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
replace_xmls:
- match_rule:
tag: arg
attribute:
- name: name
value: nameserver
parent_tag: include
parent_attribute:
- name: file
value: '$(find jsk_hrp2_ros_bridge)/launch/jsk_hrp2_ros_bridge.launch'
replaced_attribute_name: default
replaced_attribute_value: localhost
- match_rule:
tag: include
attribute:
- name: file
value: '$(find jsk_hrp2_ros_bridge)/launch/jsk_hrp2_ros_bridge.launch'
added_xml: '<arg name="CONF_FILE" value="$(find hrpsys_gazebo_tutorials)/config/HRP2JSKNTS.conf"/>'
- match_rule:
tag: include
attribute:
- name: file
value: '$(find jsk_hrp2_ros_bridge)/launch/jsk_hrp2_ros_bridge.launch'
added_xml: '<arg name="MODEL_FILE" value="$(find hrp2_models)/HRP2JSKNTS_for_OpenHRP3/HRP2JSKNTSmain.wrl"/>'
5 changes: 5 additions & 0 deletions hrpsys_gazebo_tutorials/config/hrpsys_dashboard.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
hrpsys_rtcd_start_command: "xterm -T \"RTCD\" -e 'PS1=user && source ~/.$(basename $SHELL)rc && rossetlocal && `rospack find hrpsys_gazebo_tutorials`/scripts/rtcd_start_command.sh --remote'"
hrpsys_rtcd_stop_command: "xterm -e \"pkill openhrp-model-l* && pkill rtcd\""

hrpsys_ros_bridge_start_command: "xterm -T \"Auditor\" -e \"PS1=user && source ~/.$(basename $SHELL)rc && rossetlocal && `rospack find hrpsys_gazebo_tutorials`/scripts/hrp2-launch-ros-bridge.sh\""
hrpsys_ros_bridge_stop_command: "xterm -e \"source ~/.$(basename $SHELL)rc && `rospack find hrpsys_gazebo_tutorials`/scripts/kill-ros-bridge.sh\""
Original file line number Diff line number Diff line change
Expand Up @@ -3,11 +3,12 @@
<arg name="WORLD" default="$(find hrpsys_gazebo_general)/worlds/empty.world"/>
<arg name="PAUSED" default="false"/>
<arg name="SYNCHRONIZED" default="false" />
<arg name="CALIB_FILE" default="hrp2017_xtion_calib_20170703.yaml"/>

<rosparam command="load"
file="$(find hrpsys_gazebo_tutorials)/config/HRP3HAND_L.yaml" ns="HRP3HAND_L" />
file="$(find jsk_hrp2_ros_bridge)/config/HRP2JSKNTS_gazebo_private.yaml" ns="HRP2JSKNTS" />
<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 All @@ -19,5 +20,8 @@
<arg name="SYNCHRONIZED" value="$(arg SYNCHRONIZED)" />
<arg name="USE_INSTANCE_NAME" value="true" />
<arg name="gzname" value="$(arg gzname)" />
<arg name="use_robot_state_publisher" value="false"/>
<arg name="USE_CALIBRATED_URDF" value="true"/>
<arg name="CALIB_FILE_COMMAND" value="$(find euscollada)/scripts/urdf_patch.py patch $(find hrpsys_gazebo_tutorials)/robot_models/HRP2JSKNTS/HRP2JSKNTS.urdf $(find jsk_hrp2_ros_bridge)/calib_data/$(arg CALIB_FILE)"/>
</include>
</launch>
Loading