diff --git a/.github/workflows/kinetic.yml b/.github/workflows/kinetic.yml
index 8d5bb8bd..4a712c14 100644
--- a/.github/workflows/kinetic.yml
+++ b/.github/workflows/kinetic.yml
@@ -7,13 +7,17 @@ jobs:
runs-on: ubuntu-latest
name: kinetic
- container: jskrobotics/ros-ubuntu:16.04
+ container: ubuntu:16.04
steps:
- name: Install latest git ( use sudo for ros-ubuntu, remove sudo for ubuntu container), checkout@v2 uses REST API for git<2.18, which removes .git folder and does not checkout .travis submodules
- run: sudo apt-get update && sudo apt-get install -y software-properties-common && sudo apt-get update && sudo add-apt-repository -y ppa:git-core/ppa && sudo apt-get update && sudo apt-get install -y git
- - name: Before Checkout # need for actions/checkout with ros-ubuntu container
- run: sudo chown -R user:jenkins $RUNNER_WORKSPACE $HOME
+ run: |
+ (apt-get update && apt-get install -y sudo) || echo "OK"
+ sudo apt-get update && sudo apt-get install -y software-properties-common && sudo apt-get update && sudo add-apt-repository -y ppa:git-core/ppa && sudo apt-get update && sudo apt-get install -y git
+ - name: work around permission issue # https://github.com/actions/checkout/issues/760#issuecomment-1097501613
+ run: |
+ set -x
+ git config --global --add safe.directory $GITHUB_WORKSPACE
- name: Checkout
uses: actions/checkout@v2
- name: Run jsk_travis
diff --git a/.github/workflows/melodic.yml b/.github/workflows/melodic.yml
index c1dde3b3..2ea5aae8 100644
--- a/.github/workflows/melodic.yml
+++ b/.github/workflows/melodic.yml
@@ -7,13 +7,17 @@ jobs:
runs-on: ubuntu-latest
name: melodic
- container: jskrobotics/ros-ubuntu:18.04
+ container: ubuntu:18.04
steps:
- name: Install latest git ( use sudo for ros-ubuntu, remove sudo for ubuntu container), checkout@v2 uses REST API for git<2.18, which removes .git folder and does not checkout .travis submodules
- run: sudo apt-get update && sudo apt-get install -y software-properties-common && sudo apt-get update && sudo add-apt-repository -y ppa:git-core/ppa && sudo apt-get update && sudo apt-get install -y git
- - name: Before Checkout # need for actions/checkout with ros-ubuntu container
- run: sudo chown -R user:jenkins $RUNNER_WORKSPACE $HOME
+ run: |
+ (apt-get update && apt-get install -y sudo) || echo "OK"
+ sudo apt-get update && sudo apt-get install -y software-properties-common && sudo apt-get update && sudo add-apt-repository -y ppa:git-core/ppa && sudo apt-get update && sudo apt-get install -y git
+ - name: work around permission issue # https://github.com/actions/checkout/issues/760#issuecomment-1097501613
+ run: |
+ set -x
+ git config --global --add safe.directory $GITHUB_WORKSPACE
- name: Checkout
uses: actions/checkout@v2
- name: Run jsk_travis
diff --git a/.gitignore b/.gitignore
new file mode 100644
index 00000000..42ac4ba7
--- /dev/null
+++ b/.gitignore
@@ -0,0 +1,23 @@
+# Emacs
+*~
+\#*\#
+.\#*
+
+# generated files from hrpsys_choreonoid
+hrpsys_choreonoid/lib/
+hrpsys_choreonoid/*.so
+
+# generated files from jvrc_models
+jvrc_models/model
+
+# generated files from hrpsys_ros_bridge/cmake/compile_robot_model.cmake
+hrpsys_choreonoid_tutorials/models/*.conf
+hrpsys_choreonoid_tutorials/models/*.xml
+hrpsys_choreonoid_tutorials/models/*.l
+hrpsys_choreonoid_tutorials/models/*.dae
+hrpsys_choreonoid_tutorials/models/*/*.dae
+hrpsys_choreonoid_tutorials/models/*.urdf
+
+# generated files from hrpsys_choreonoid_tutorials configure_file
+hrpsys_choreonoid_tutorials/config/*.cnoid
+hrpsys_choreonoid_tutorials/config/*.yaml
diff --git a/hrpsys_choreonoid_tutorials/config/TABLIS_BASE_RH_FLAT.cnoid.in b/hrpsys_choreonoid_tutorials/config/TABLIS_BASE_RH_FLAT.cnoid.in
index d23ea15f..ef96aa5a 100644
--- a/hrpsys_choreonoid_tutorials/config/TABLIS_BASE_RH_FLAT.cnoid.in
+++ b/hrpsys_choreonoid_tutorials/config/TABLIS_BASE_RH_FLAT.cnoid.in
@@ -29,8 +29,8 @@ items:
jointPositions: [0, 0, -0.174532925, 0.523598776, -0.34906585, 0,
0, 0, -0.174532925, 0.523598776, -0.34906585, 0,
0,
- 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0]
+ 0, 0, 0, 0, 0, 0, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0]
initialRootPosition: [ 0.0, 0.0, 1.44 ]
initialRootAttitude: [
0, -1, 0,
@@ -39,8 +39,8 @@ items:
initialJointPositions: [0, 0, -0.174532925, 0.523598776, -0.34906585, 0,
0, 0, -0.174532925, 0.523598776, -0.34906585, 0,
0,
- 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0]
+ 0, 0, 0, 0, 0, 0, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0]
zmp: [ 0, 0, 0 ]
collisionDetection: true
selfCollisionDetection: false
diff --git a/hrpsys_choreonoid_tutorials/config/TABLIS_RH_FLAT.cnoid.in b/hrpsys_choreonoid_tutorials/config/TABLIS_RH_FLAT.cnoid.in
index ac310b6d..6052b309 100644
--- a/hrpsys_choreonoid_tutorials/config/TABLIS_RH_FLAT.cnoid.in
+++ b/hrpsys_choreonoid_tutorials/config/TABLIS_RH_FLAT.cnoid.in
@@ -29,8 +29,8 @@ items:
jointPositions: [0, 0, -0.174532925, 0.523598776, -0.34906585, 0,
0, 0, -0.174532925, 0.523598776, -0.34906585, 0,
0,
- 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0]
+ 0, 0, 0, 0, 0, 0, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0]
initialRootPosition: [ 0.0, 0.0, 1.27 ]
initialRootAttitude: [
0, -1, 0,
@@ -39,8 +39,8 @@ items:
initialJointPositions: [0, 0, -0.174532925, 0.523598776, -0.34906585, 0,
0, 0, -0.174532925, 0.523598776, -0.34906585, 0,
0,
- 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0]
+ 0, 0, 0, 0, 0, 0, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0]
zmp: [ 0, 0, 0 ]
collisionDetection: true
selfCollisionDetection: false
diff --git a/hrpsys_choreonoid_tutorials/config/floor.yaml b/hrpsys_choreonoid_tutorials/config/floor.yaml
new file mode 100644
index 00000000..9ba61a95
--- /dev/null
+++ b/hrpsys_choreonoid_tutorials/config/floor.yaml
@@ -0,0 +1,5 @@
+obj1:
+ name: 'VISIBLE_FLOOR'
+ file: '$(find choreonoid)/share/model/misc/floor.body'
+ translation: [0, 0, -0.1]
+ rotation: [[1, 0, 0], [0, 1, 0], [0, 0, 1]]
diff --git a/hrpsys_choreonoid_tutorials/config/footsal.yaml.in b/hrpsys_choreonoid_tutorials/config/footsal.yaml.in
index dab442fc..463fafbb 100644
--- a/hrpsys_choreonoid_tutorials/config/footsal.yaml.in
+++ b/hrpsys_choreonoid_tutorials/config/footsal.yaml.in
@@ -6,12 +6,12 @@ obj1:
obj2:
name: 'GOAL'
file: '@jvrc_models_MODEL_DIR@/models/footsal_goal.wrl'
- translation: [9.5, 0.0, 0.0]
- rotation: [[1, 0, 0], [0, 1, 0], [0, 0, 1]]
+ translation: [0.0, 9.5, 0.0]
+ rotation: [[0, -1, 0], [1, 0, 0], [0, 0, 1]]
obj3:
name: 'BALL'
file: '@jvrc_models_MODEL_DIR@/models/yellow_ball.wrl'
- translation: [2.0, 0.0, 0.12]
+ translation: [0.0, 2.0, 0.12]
rotation: [[1, 0, 0], [0, 1, 0], [0, 0, 1]]
obj4:
name: 'WALL_BACK'
diff --git a/hrpsys_choreonoid_tutorials/config/soccer.yaml.in b/hrpsys_choreonoid_tutorials/config/soccer.yaml.in
index c1fcee51..3958777e 100644
--- a/hrpsys_choreonoid_tutorials/config/soccer.yaml.in
+++ b/hrpsys_choreonoid_tutorials/config/soccer.yaml.in
@@ -6,12 +6,12 @@ obj1:
obj2:
name: 'GOAL'
file: '@jvrc_models_MODEL_DIR@/models/soccer_goal.wrl'
- translation: [26.0, 0.0, 0.0]
- rotation: [[1, 0, 0], [0, 1, 0], [0, 0, 1]]
+ translation: [0.0, 26.0, 0.0]
+ rotation: [[0, -1, 0], [1, 0, 0], [0, 0, 1]]
obj3:
name: 'BALL'
file: '@jvrc_models_MODEL_DIR@/models/yellow_ball.wrl'
- translation: [2.0, 0.0, 0.12]
+ translation: [0.0, 2.0, 0.12]
rotation: [[1, 0, 0], [0, 1, 0], [0, 0, 1]]
obj4:
name: 'WALL_BACK'
diff --git a/hrpsys_choreonoid_tutorials/euslisp/action_and_perception/kick-ball-demo.l b/hrpsys_choreonoid_tutorials/euslisp/action_and_perception/kick-ball-demo.l
index 5719730b..49d3677a 100644
--- a/hrpsys_choreonoid_tutorials/euslisp/action_and_perception/kick-ball-demo.l
+++ b/hrpsys_choreonoid_tutorials/euslisp/action_and_perception/kick-ball-demo.l
@@ -94,8 +94,8 @@
(defun ball-is-goalq ()
(let ((pos (send (get-coords-on-simulation :robot "BALL") :worldpos)))
- (and (> (elt pos 0) 9600)
- (> 1560 (elt pos 1) -1560)
+ (and (> (elt pos 1) 9600)
+ (> 1560 (elt pos 0) -1560)
(> 2200 (elt pos 2) 0))
))
diff --git a/hrpsys_choreonoid_tutorials/launch/perception/image_processing.launch b/hrpsys_choreonoid_tutorials/launch/perception/image_processing.launch
index db768c5f..06e2a990 100644
--- a/hrpsys_choreonoid_tutorials/launch/perception/image_processing.launch
+++ b/hrpsys_choreonoid_tutorials/launch/perception/image_processing.launch
@@ -1,5 +1,6 @@
+
@@ -67,5 +68,31 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/hrpsys_choreonoid_tutorials/launch/perception/tracking_recognition.launch b/hrpsys_choreonoid_tutorials/launch/perception/tracking_recognition.launch
index 2416dc3f..1eb81200 100644
--- a/hrpsys_choreonoid_tutorials/launch/perception/tracking_recognition.launch
+++ b/hrpsys_choreonoid_tutorials/launch/perception/tracking_recognition.launch
@@ -1,8 +1,9 @@
-
+
+
-
-
-
+
+
+
diff --git a/hrpsys_choreonoid_tutorials/launch/tablis_choreonoid.launch b/hrpsys_choreonoid_tutorials/launch/tablis_choreonoid.launch
index e356a5b1..2f6b1986 100644
--- a/hrpsys_choreonoid_tutorials/launch/tablis_choreonoid.launch
+++ b/hrpsys_choreonoid_tutorials/launch/tablis_choreonoid.launch
@@ -46,9 +46,9 @@
-
-
-
+
+
+
diff --git a/hrpsys_choreonoid_tutorials/models/JAXON_JVRC.PDgains.sav b/hrpsys_choreonoid_tutorials/models/JAXON_JVRC.PDgains.sav
index 47f2f181..5e9bd811 100644
--- a/hrpsys_choreonoid_tutorials/models/JAXON_JVRC.PDgains.sav
+++ b/hrpsys_choreonoid_tutorials/models/JAXON_JVRC.PDgains.sav
@@ -1,38 +1,38 @@
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
-1 0 1
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
+1 0 1 1 0 0
diff --git a/hrpsys_choreonoid_tutorials/models/JAXON_JVRC.PDgains_sim.dat b/hrpsys_choreonoid_tutorials/models/JAXON_JVRC.PDgains_sim.dat
index 122eae18..18d11fe4 100644
--- a/hrpsys_choreonoid_tutorials/models/JAXON_JVRC.PDgains_sim.dat
+++ b/hrpsys_choreonoid_tutorials/models/JAXON_JVRC.PDgains_sim.dat
@@ -1,38 +1,38 @@
-33000 240
-83000 240
-33000 240
-33000 240
-47000 240
-33000 240
-33000 240
-83000 240
-33000 240
-33000 240
-47000 240
-33000 240
-83000 240
-83000 240
-83000 240
-10000 200
-10000 200
-20000 320
-20000 320
-20000 320
-20000 320
-20000 320
-20000 320
-20000 320
-20000 320
-20000 320
-20000 320
-20000 320
-20000 320
-20000 320
-20000 320
-20000 320
-20000 320
-400 10
-400 10
-400 10
-400 10
-100 5
+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
+83000 240 1 0
+83000 240 1 0
+83000 240 1 0
+10000 200 1 0
+10000 200 1 0
+20000 320 1 0
+20000 320 1 0
+20000 320 1 0
+20000 320 1 0
+20000 320 1 0
+20000 320 1 0
+20000 320 1 0
+20000 320 1 0
+20000 320 1 0
+20000 320 1 0
+20000 320 1 0
+20000 320 1 0
+20000 320 1 0
+20000 320 1 0
+20000 320 1 0
+20000 320 1 0
+400 10 1 0
+400 10 1 0
+400 10 1 0
+400 10 1 0
+100 5 1 0
diff --git a/hrpsys_choreonoid_tutorials/scripts/chidori_rh_setup.py b/hrpsys_choreonoid_tutorials/scripts/chidori_rh_setup.py
index d075287b..1ce9d1e1 100755
--- a/hrpsys_choreonoid_tutorials/scripts/chidori_rh_setup.py
+++ b/hrpsys_choreonoid_tutorials/scripts/chidori_rh_setup.py
@@ -13,15 +13,15 @@ def getRTCList (self):
['kf', "KalmanFilter"],
#['vs', "VirtualForceSensor"],
['rmfo', "RemoveForceSensorLinkOffset"],
+ ['octd', "ObjectContactTurnaroundDetector"],
['es', "EmergencyStopper"],
['rfu', "ReferenceForceUpdater"],
- ['octd', "ObjectContactTurnaroundDetector"],
['ic', "ImpedanceController"],
['abc', "AutoBalancer"],
['st', "Stabilizer"],
- # ['tc', "TorqueController"],
- # ['te', "ThermoEstimator"],
# ['tl', "ThermoLimiter"],
+ # ['te', "ThermoEstimator"],
+ # ['tc', "TorqueController"],
['co', "CollisionDetector"],
['hes', "EmergencyStopper"],
['el', "SoftErrorLimiter"],
diff --git a/hrpsys_choreonoid_tutorials/scripts/jaxon_blue_rh_setup.py b/hrpsys_choreonoid_tutorials/scripts/jaxon_blue_rh_setup.py
index a632c136..4d8de3cf 100755
--- a/hrpsys_choreonoid_tutorials/scripts/jaxon_blue_rh_setup.py
+++ b/hrpsys_choreonoid_tutorials/scripts/jaxon_blue_rh_setup.py
@@ -13,16 +13,16 @@ def getRTCList (self):
['kf', "KalmanFilter"],
['vs', "VirtualForceSensor"],
['rmfo', "RemoveForceSensorLinkOffset"],
+ ['octd', "ObjectContactTurnaroundDetector"],
['es', "EmergencyStopper"],
+ ['rfu', "ReferenceForceUpdater"],
['ic', "ImpedanceController"],
['abc', "AutoBalancer"],
['st', "Stabilizer"],
- ['co', "CollisionDetector"],
- # ['tc', "TorqueController"],
- # ['te', "ThermoEstimator"],
# ['tl', "ThermoLimiter"],
- ['rfu', "ReferenceForceUpdater"],
- ['octd', "ObjectContactTurnaroundDetector"],
+ # ['te', "ThermoEstimator"],
+ # ['tc', "TorqueController"],
+ ['co', "CollisionDetector"],
['hes', "EmergencyStopper"],
['el', "SoftErrorLimiter"],
['log', "DataLogger"]
@@ -42,7 +42,6 @@ def defJointGroups (self):
def startABSTIMP (self):
### not used on hrpsys
- # self.el_svc.setServoErrorLimit("motor_joint", sys.float_info.max)
# self.el_svc.setServoErrorLimit("RARM_F_JOINT0", sys.float_info.max)
# self.el_svc.setServoErrorLimit("RARM_F_JOINT1", sys.float_info.max)
# self.el_svc.setServoErrorLimit("LARM_F_JOINT0", sys.float_info.max)
diff --git a/hrpsys_choreonoid_tutorials/scripts/jaxon_red_rh_setup.py b/hrpsys_choreonoid_tutorials/scripts/jaxon_red_rh_setup.py
index 4538ed10..80618c8c 100755
--- a/hrpsys_choreonoid_tutorials/scripts/jaxon_red_rh_setup.py
+++ b/hrpsys_choreonoid_tutorials/scripts/jaxon_red_rh_setup.py
@@ -13,16 +13,16 @@ def getRTCList (self):
['kf', "KalmanFilter"],
['vs', "VirtualForceSensor"],
['rmfo', "RemoveForceSensorLinkOffset"],
+ ['octd', "ObjectContactTurnaroundDetector"],
['es', "EmergencyStopper"],
+ ['rfu', "ReferenceForceUpdater"],
['ic', "ImpedanceController"],
['abc', "AutoBalancer"],
['st', "Stabilizer"],
- ['co', "CollisionDetector"],
- # ['tc', "TorqueController"],
- # ['te', "ThermoEstimator"],
# ['tl', "ThermoLimiter"],
- ['rfu', "ReferenceForceUpdater"],
- ['octd', "ObjectContactTurnaroundDetector"],
+ # ['te', "ThermoEstimator"],
+ # ['tc', "TorqueController"],
+ ['co', "CollisionDetector"],
['hes', "EmergencyStopper"],
['el', "SoftErrorLimiter"],
['log', "DataLogger"]
@@ -42,7 +42,6 @@ def defJointGroups (self):
def startABSTIMP (self):
### not used on hrpsys
- self.el_svc.setServoErrorLimit("motor_joint", sys.float_info.max)
self.el_svc.setServoErrorLimit("RARM_F_JOINT0", sys.float_info.max)
self.el_svc.setServoErrorLimit("RARM_F_JOINT1", sys.float_info.max)
self.el_svc.setServoErrorLimit("LARM_F_JOINT0", sys.float_info.max)
diff --git a/hrpsys_choreonoid_tutorials/scripts/jaxon_red_setup.py b/hrpsys_choreonoid_tutorials/scripts/jaxon_red_setup.py
index 366b38af..6dad888f 100755
--- a/hrpsys_choreonoid_tutorials/scripts/jaxon_red_setup.py
+++ b/hrpsys_choreonoid_tutorials/scripts/jaxon_red_setup.py
@@ -13,16 +13,16 @@ def getRTCList (self):
['kf', "KalmanFilter"],
['vs', "VirtualForceSensor"],
['rmfo', "RemoveForceSensorLinkOffset"],
+ ['octd', "ObjectContactTurnaroundDetector"],
['es', "EmergencyStopper"],
+ ['rfu', "ReferenceForceUpdater"],
['ic', "ImpedanceController"],
['abc', "AutoBalancer"],
['st', "Stabilizer"],
- ['co', "CollisionDetector"],
- # ['tc', "TorqueController"],
- # ['te', "ThermoEstimator"],
# ['tl', "ThermoLimiter"],
- ['rfu', "ReferenceForceUpdater"],
- ['octd', "ObjectContactTurnaroundDetector"],
+ # ['te', "ThermoEstimator"],
+ # ['tc', "TorqueController"],
+ ['co', "CollisionDetector"],
['hes', "EmergencyStopper"],
['el', "SoftErrorLimiter"],
['log', "DataLogger"]
@@ -42,7 +42,6 @@ def defJointGroups (self):
def startABSTIMP (self):
### not used on hrpsys
- self.el_svc.setServoErrorLimit("motor_joint", sys.float_info.max)
self.el_svc.setServoErrorLimit("RARM_F_JOINT0", sys.float_info.max)
self.el_svc.setServoErrorLimit("RARM_F_JOINT1", sys.float_info.max)
self.el_svc.setServoErrorLimit("LARM_F_JOINT0", sys.float_info.max)
diff --git a/hrpsys_choreonoid_tutorials/scripts/tablis_base_rh_setup.py b/hrpsys_choreonoid_tutorials/scripts/tablis_base_rh_setup.py
index b76f17ee..64e7fd8a 100755
--- a/hrpsys_choreonoid_tutorials/scripts/tablis_base_rh_setup.py
+++ b/hrpsys_choreonoid_tutorials/scripts/tablis_base_rh_setup.py
@@ -3,6 +3,24 @@
from hrpsys_choreonoid_tutorials.choreonoid_hrpsys_config import *
class TABLIS_HrpsysConfigurator(ChoreonoidHrpsysConfigurator):
+ def getRTCList(self):
+ return [
+ ['seq', "SequencePlayer"],
+ ['sh', "StateHolder"],
+ ['fk', "ForwardKinematics"],
+ ['kf', "KalmanFilter"],
+ ['rmfo', "RemoveForceSensorLinkOffset"],
+ # ['octd', "ObjectContactTurnaroundDetector"],
+ # ['es', "EmergencyStopper"],
+ # ['rfu', "ReferenceForceUpdater"],
+ # ['ic', "ImpedanceController"],
+ # ['abc', "AutoBalancer"],
+ # ['st', "Stabilizer"],
+ # ['co', "CollisionDetector"],
+ # ['hes', "EmergencyStopper"],
+ # ['el', "SoftErrorLimiter"],
+ ['log', "DataLogger"]
+ ]
def startABSTIMP (self):
self.rh_svc.setServoGainPercentage("all",100)
# self.startAutoBalancer()
diff --git a/hrpsys_choreonoid_tutorials/scripts/tablis_rh_setup.py b/hrpsys_choreonoid_tutorials/scripts/tablis_rh_setup.py
index 980a8df5..53167c44 100755
--- a/hrpsys_choreonoid_tutorials/scripts/tablis_rh_setup.py
+++ b/hrpsys_choreonoid_tutorials/scripts/tablis_rh_setup.py
@@ -3,10 +3,29 @@
from hrpsys_choreonoid_tutorials.choreonoid_hrpsys_config import *
class TABLIS_HrpsysConfigurator(ChoreonoidHrpsysConfigurator):
+ def getRTCList(self):
+ return [
+ ['seq', "SequencePlayer"],
+ ['sh', "StateHolder"],
+ ['fk', "ForwardKinematics"],
+ ['kf', "KalmanFilter"],
+ ['rmfo', "RemoveForceSensorLinkOffset"],
+ # ['octd', "ObjectContactTurnaroundDetector"],
+ # ['es', "EmergencyStopper"],
+ # ['rfu', "ReferenceForceUpdater"],
+ # ['ic', "ImpedanceController"],
+ # ['abc', "AutoBalancer"],
+ # ['st', "Stabilizer"],
+ # ['co', "CollisionDetector"],
+ # ['hes', "EmergencyStopper"],
+ # ['el', "SoftErrorLimiter"],
+ ['log', "DataLogger"]
+ ]
def startABSTIMP (self):
- self.startAutoBalancer()
- self.setResetPose()
- self.startStabilizer()
+ #self.startAutoBalancer()
+ #self.setResetPose()
+ #self.startStabilizer()
+ pass
if __name__ == '__main__':
hcf = TABLIS_HrpsysConfigurator("TABLIS")
diff --git a/hrpsys_choreonoid_tutorials/src/hrpsys_choreonoid_tutorials/choreonoid_hrpsys_config.py b/hrpsys_choreonoid_tutorials/src/hrpsys_choreonoid_tutorials/choreonoid_hrpsys_config.py
index 56794004..b629c26d 100755
--- a/hrpsys_choreonoid_tutorials/src/hrpsys_choreonoid_tutorials/choreonoid_hrpsys_config.py
+++ b/hrpsys_choreonoid_tutorials/src/hrpsys_choreonoid_tutorials/choreonoid_hrpsys_config.py
@@ -17,10 +17,10 @@ def getRTCList (self):
['ic', "ImpedanceController"],
['abc', "AutoBalancer"],
['st', "Stabilizer"],
- ['co', "CollisionDetector"],
- # ['tc', "TorqueController"],
- # ['te', "ThermoEstimator"],
# ['tl', "ThermoLimiter"],
+ # ['te', "ThermoEstimator"],
+ # ['tc', "TorqueController"],
+ ['co', "CollisionDetector"],
['hes', "EmergencyStopper"],
['el', "SoftErrorLimiter"],
['log', "DataLogger"]
diff --git a/jvrc_models/JAXON_JVRC/JAXON_JVRCmain.wrl b/jvrc_models/JAXON_JVRC/JAXON_JVRCmain.wrl
index 6724eff6..9fe7ccfe 100644
--- a/jvrc_models/JAXON_JVRC/JAXON_JVRCmain.wrl
+++ b/jvrc_models/JAXON_JVRC/JAXON_JVRCmain.wrl
@@ -771,11 +771,8 @@ DEF JAXON_JVRC Humanoid {
momentsOfInertia [0.020752 -1.298590e-06 8.029880e-06 -1.298590e-06 0.0198 0.000501 8.029880e-06 0.000501 0.013089]
children [
Inline { url "LARM_LINK7_JVRC.wrl" }
- # DEF lhsensor ForceSensor{
- # translation 0 0 -0.069
- # rotation 0.382683 -0.92388 -0 3.14159
- DEF lhsensor ForceSensor{ ## 2019/07 wacoh
- translation 0 0 -0.09
+ DEF lhsensor ForceSensor{ ##2022/05 leptrino
+ translation 0 0 -0.076
rotation 0 1 0 3.14159
sensorId 3
} #Sensor
@@ -1109,12 +1106,9 @@ DEF JAXON_JVRC Humanoid {
momentsOfInertia [0.020752 1.298590e-06 -8.029880e-06 1.298590e-06 0.0198 -0.000501 -8.029880e-06 -0.000501 0.013089]
children [
Inline { url "RARM_LINK7_JVRC.wrl" }
- # DEF rhsensor ForceSensor{
- # translation 0 0 -0.069
- # rotation -0.382683 -0.92388 -0 3.14159
- DEF rhsensor ForceSensor{ ## 2019/07 wacoh
- translation 0 0 -0.09
- rotation 0 1 0 3.14159
+ DEF rhsensor ForceSensor{ ##2022/05 leptrino
+ translation 0 0 -0.076
+ rotation 1 0 0 3.14159
sensorId 2
} #Sensor
]
diff --git a/jvrc_models/JAXON_JVRC/JAXON_JVRCmain_hrpsys.wrl b/jvrc_models/JAXON_JVRC/JAXON_JVRCmain_hrpsys.wrl
index 4ac21151..07040280 100644
--- a/jvrc_models/JAXON_JVRC/JAXON_JVRCmain_hrpsys.wrl
+++ b/jvrc_models/JAXON_JVRC/JAXON_JVRCmain_hrpsys.wrl
@@ -771,11 +771,8 @@ DEF JAXON_JVRC Humanoid {
momentsOfInertia [0.020752 -1.298590e-06 8.029880e-06 -1.298590e-06 0.0198 0.000501 8.029880e-06 0.000501 0.013089]
children [
Inline { url "LARM_LINK7_JVRC.wrl" }
- # DEF lhsensor ForceSensor{
- # translation 0 0 -0.069
- # rotation 0.382683 -0.92388 -0 3.14159
- DEF lhsensor ForceSensor{ ## 2019/07 wacoh
- translation 0 0 -0.09
+ DEF lhsensor ForceSensor{ ##2022/05 leptrino
+ translation 0 0 -0.076
rotation 0 1 0 3.14159
sensorId 3
} #Sensor
@@ -1110,12 +1107,9 @@ DEF JAXON_JVRC Humanoid {
momentsOfInertia [0.020752 1.298590e-06 -8.029880e-06 1.298590e-06 0.0198 -0.000501 -8.029880e-06 -0.000501 0.013089]
children [
Inline { url "RARM_LINK7_JVRC.wrl" }
- # DEF rhsensor ForceSensor{
- # translation 0 0 -0.069
- # rotation -0.382683 -0.92388 -0 3.14159
- DEF rhsensor ForceSensor{ ## 2019/07 wacoh
- translation 0 0 -0.09
- rotation 0 1 0 3.14159
+ DEF rhsensor ForceSensor{ ##2022/05 leptrino
+ translation 0 0 -0.076
+ rotation 1 0 0 3.14159
sensorId 2
} #Sensor
]
diff --git a/jvrc_models/JAXON_JVRC/JAXON_JVRCmain_hrpsys_bush.wrl b/jvrc_models/JAXON_JVRC/JAXON_JVRCmain_hrpsys_bush.wrl
index fdf5032d..fa451f78 100644
--- a/jvrc_models/JAXON_JVRC/JAXON_JVRCmain_hrpsys_bush.wrl
+++ b/jvrc_models/JAXON_JVRC/JAXON_JVRCmain_hrpsys_bush.wrl
@@ -848,11 +848,8 @@ DEF JAXON_JVRC Humanoid {
# Inline { url "../models/checkerboard.wrl" }
# ]
#}
- # DEF lhsensor ForceSensor{
- # translation 0 0 -0.069
- # rotation 0.382683 -0.92388 -0 3.14159
- DEF lhsensor ForceSensor{ ## 2019/07 wacoh
- translation 0 0 -0.09
+ DEF lhsensor ForceSensor{ ##2022/05 leptrino
+ translation 0 0 -0.076
rotation 0 1 0 3.14159
sensorId 3
} #Sensor
@@ -1225,12 +1222,9 @@ DEF JAXON_JVRC Humanoid {
# Inline { url "../models/checkerboard.wrl" }
# ]
#}
- # DEF rhsensor ForceSensor{
- # translation 0 0 -0.069
- # rotation -0.382683 -0.92388 -0 3.14159
- DEF rhsensor ForceSensor{ ## 2019/07 wacoh
- translation 0 0 -0.09
- rotation 0 1 0 3.14159
+ DEF rhsensor ForceSensor{ ##2022/05 leptrino
+ translation 0 0 -0.076
+ rotation 1 0 0 3.14159
sensorId 2
} #Sensor
]