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

Add examples for samplerobot #252

Merged
merged 4 commits into from
Jul 15, 2014
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
1 change: 1 addition & 0 deletions sample/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ endif()

add_subdirectory(PA10)
add_subdirectory(HRP4C)
add_subdirectory(SampleRobot)

install(PROGRAMS
simTest1.py simTest2.py simTest3.py simTest4.py simTest5.py
Expand Down
35 changes: 35 additions & 0 deletions sample/SampleRobot/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
# generate .conf and .xml files for two controller period
set(controller_time_list 0.002 0.005) # [s]
set(controller_period_list 500 200) # [Hz]
foreach(_idx 0 1)
list(GET controller_time_list ${_idx} _tmp_controller_time)
list(GET controller_period_list ${_idx} _tmp_controller_period)
set(CONTROLLER_TIME ${_tmp_controller_time})
set(CONTROLLER_PERIOD ${_tmp_controller_period})
configure_file(SampleRobot.RobotHardware.conf.in ${CMAKE_CURRENT_BINARY_DIR}/SampleRobot.RobotHardware.${_tmp_controller_period}.conf)
configure_file(SampleRobot.xml.in ${CMAKE_CURRENT_BINARY_DIR}/SampleRobot.${_tmp_controller_period}.xml)
configure_file(SampleRobot.conf.in ${CMAKE_CURRENT_BINARY_DIR}/SampleRobot.${_tmp_controller_period}.conf)
endforeach()

configure_file(samplerobot_walk.py.in ${CMAKE_CURRENT_BINARY_DIR}/samplerobot_walk.py)

install(PROGRAMS
samplerobot_data_logger.py
samplerobot_auto_balancer.py
samplerobot_stabilizer.py
samplerobot_remove_force_offset.py
samplerobot_impedance_controller.py
${CMAKE_CURRENT_BINARY_DIR}/samplerobot_walk.py
DESTINATION share/hrpsys/samples/SampleRobot)

install(FILES
# files for 500[Hz] = 0.002[s]
${CMAKE_CURRENT_BINARY_DIR}/SampleRobot.500.conf
${CMAKE_CURRENT_BINARY_DIR}/SampleRobot.500.xml
${CMAKE_CURRENT_BINARY_DIR}/SampleRobot.RobotHardware.500.conf
# files for 200[Hz] = 0.005[s]
${CMAKE_CURRENT_BINARY_DIR}/SampleRobot.200.conf
${CMAKE_CURRENT_BINARY_DIR}/SampleRobot.200.xml
${CMAKE_CURRENT_BINARY_DIR}/SampleRobot.RobotHardware.200.conf
DESTINATION share/hrpsys/samples/SampleRobot)

5 changes: 5 additions & 0 deletions sample/SampleRobot/SampleRobot.RobotHardware.conf.in
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
model: file://@OPENHRP_DIR@/share/OpenHRP-3.1/sample/model/sample1.wrl
exec_cxt.periodic.type: hrpExecutionContext
exec_cxt.periodic.rate: @CONTROLLER_PERIOD@


6 changes: 6 additions & 0 deletions sample/SampleRobot/SampleRobot.conf.in
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
model: file://@OPENHRP_DIR@/share/OpenHRP-3.1/sample/model/sample1.wrl
dt: @CONTROLLER_TIME@

abc_leg_offset: 0,0.09,0
abc_stride_parameter: 0.15,0.05,10
end_effectors: :rarm,RARM_WRIST_P,CHEST,0.0,-5.684342e-17,-0.12,9.813078e-18,1.0,0.0,1.5708, :larm,LARM_WRIST_P,CHEST,0.0,5.684342e-17,-0.12,-9.813078e-18,1.0,0.0,1.5708, :rleg,RLEG_ANKLE_R,WAIST,0.0,0.0,-0.07,0.0,0.0,0.0,0.0, :lleg,LLEG_ANKLE_R,WAIST,0.0,0.0,-0.07,0.0,0.0,0.0,0.0,
192 changes: 192 additions & 0 deletions sample/SampleRobot/SampleRobot.xml.in
Original file line number Diff line number Diff line change
@@ -0,0 +1,192 @@
<grxui>
<mode name="Simulation">
<item class="com.generalrobotix.ui.item.GrxSimulationItem" name="simulationItem">
<property name="integrate" value="true"/>
<property name="timeStep" value="@CONTROLLER_TIME@"/>
<property name="totalTime" value="2000000.0"/>
<property name="method" value="EULER"/>
</item>
<item class="com.generalrobotix.ui.item.GrxRTSItem" name="SampleRobot" select="true">
<property name="SampleRobot(Robot)0.period" value="@CONTROLLER_TIME@"/>
<property name="HGcontroller0.period" value="@CONTROLLER_TIME@"/>
<property name="HGcontroller0.factory" value="HGcontroller"/>
<property name="connection" value="HGcontroller0.qOut:SampleRobot(Robot)0.qRef"/>
<property name="connection" value="HGcontroller0.dqOut:SampleRobot(Robot)0.dqRef"/>
<property name="connection" value="HGcontroller0.ddqOut:SampleRobot(Robot)0.ddqRef"/>
</item>
<item class="com.generalrobotix.ui.item.GrxModelItem" name="sample1" url="@OPENHRP_DIR@/share/OpenHRP-3.1/sample/model/sample1.wrl">
<property name="rtcName" value="SampleRobot(Robot)0"/>
<property name="inport" value="qRef:JOINT_VALUE"/>
<property name="inport" value="dqRef:JOINT_VELOCITY"/>
<property name="inport" value="ddqRef:JOINT_ACCELERATION"/>
<property name="outport" value="q:JOINT_VALUE"/>
<property name="outport" value="tau:JOINT_TORQUE"/>
<property name="outport" value="lfsensor:lfsensor:FORCE_SENSOR"/>
<property name="outport" value="rfsensor:rfsensor:FORCE_SENSOR"/>
<property name="outport" value="lhsensor:lhsensor:FORCE_SENSOR"/>
<property name="outport" value="rhsensor:rhsensor:FORCE_SENSOR"/>
<property name="outport" value="gyrometer:gyrometer:RATE_GYRO_SENSOR"/>
<property name="outport" value="gsensor:gsensor:ACCELERATION_SENSOR"/>
<property name="WAIST.NumOfAABB" value="1"/>
<property name="WAIST.translation" value="0 0 0.7235"/>
<property name="WAIST.rotation" value="1 0 0 0"/>
<property name="WAIST.mode" value="Torque"/>
<property name="controller" value="SampleRobot"/>
<property name="RLEG_HIP_R.angle" value="0.0"/>
<property name="RLEG_HIP_R.mode" value="HighGain"/>
<property name="RLEG_HIP_R.NumOfAABB" value="1"/>
<property name="RLEG_HIP_P.angle" value="0.0"/>
<property name="RLEG_HIP_P.mode" value="HighGain"/>
<property name="RLEG_HIP_P.NumOfAABB" value="1"/>
<property name="RLEG_HIP_Y.angle" value="0.0"/>
<property name="RLEG_HIP_Y.mode" value="HighGain"/>
<property name="RLEG_HIP_Y.NumOfAABB" value="1"/>
<property name="RLEG_KNEE.angle" value="0.0"/>
<property name="RLEG_KNEE.mode" value="HighGain"/>
<property name="RLEG_KNEE.NumOfAABB" value="1"/>
<property name="RLEG_ANKLE_P.angle" value="0.0"/>
<property name="RLEG_ANKLE_P.mode" value="HighGain"/>
<property name="RLEG_ANKLE_P.NumOfAABB" value="1"/>
<property name="RLEG_ANKLE_R.angle" value="0.0"/>
<property name="RLEG_ANKLE_R.mode" value="HighGain"/>
<property name="RLEG_ANKLE_R.NumOfAABB" value="1"/>
<property name="RARM_SHOULDER_P.angle" value="0.0"/>
<property name="RARM_SHOULDER_P.mode" value="HighGain"/>
<property name="RARM_SHOULDER_P.NumOfAABB" value="1"/>
<property name="RARM_SHOULDER_R.angle" value="0.0"/>
<property name="RARM_SHOULDER_R.mode" value="HighGain"/>
<property name="RARM_SHOULDER_R.NumOfAABB" value="1"/>
<property name="RARM_SHOULDER_Y.angle" value="0.0"/>
<property name="RARM_SHOULDER_Y.mode" value="HighGain"/>
<property name="RARM_SHOULDER_Y.NumOfAABB" value="1"/>
<property name="RARM_ELBOW.angle" value="0.0"/>
<property name="RARM_ELBOW.mode" value="HighGain"/>
<property name="RARM_ELBOW.NumOfAABB" value="1"/>
<property name="RARM_WRIST_Y.angle" value="0.0"/>
<property name="RARM_WRIST_Y.mode" value="HighGain"/>
<property name="RARM_WRIST_Y.NumOfAABB" value="1"/>
<property name="RARM_WRIST_P.angle" value="0.0"/>
<property name="RARM_WRIST_P.mode" value="HighGain"/>
<property name="RARM_WRIST_P.NumOfAABB" value="1"/>
<property name="RARM_WRIST_R.angle" value="0.0"/>
<property name="RARM_WRIST_R.mode" value="HighGain"/>
<property name="RARM_WRIST_R.NumOfAABB" value="1"/>
<property name="LLEG_HIP_R.angle" value="0.0"/>
<property name="LLEG_HIP_R.mode" value="HighGain"/>
<property name="LLEG_HIP_R.NumOfAABB" value="1"/>
<property name="LLEG_HIP_P.angle" value="0.0"/>
<property name="LLEG_HIP_P.mode" value="HighGain"/>
<property name="LLEG_HIP_P.NumOfAABB" value="1"/>
<property name="LLEG_HIP_Y.angle" value="0.0"/>
<property name="LLEG_HIP_Y.mode" value="HighGain"/>
<property name="LLEG_HIP_Y.NumOfAABB" value="1"/>
<property name="LLEG_KNEE.angle" value="0.0"/>
<property name="LLEG_KNEE.mode" value="HighGain"/>
<property name="LLEG_KNEE.NumOfAABB" value="1"/>
<property name="LLEG_ANKLE_P.angle" value="0.0"/>
<property name="LLEG_ANKLE_P.mode" value="HighGain"/>
<property name="LLEG_ANKLE_P.NumOfAABB" value="1"/>
<property name="LLEG_ANKLE_R.angle" value="0.0"/>
<property name="LLEG_ANKLE_R.mode" value="HighGain"/>
<property name="LLEG_ANKLE_R.NumOfAABB" value="1"/>
<property name="LARM_SHOULDER_P.angle" value="0.0"/>
<property name="LARM_SHOULDER_P.mode" value="HighGain"/>
<property name="LARM_SHOULDER_P.NumOfAABB" value="1"/>
<property name="LARM_SHOULDER_R.angle" value="0.0"/>
<property name="LARM_SHOULDER_R.mode" value="HighGain"/>
<property name="LARM_SHOULDER_R.NumOfAABB" value="1"/>
<property name="LARM_SHOULDER_Y.angle" value="0.0"/>
<property name="LARM_SHOULDER_Y.mode" value="HighGain"/>
<property name="LARM_SHOULDER_Y.NumOfAABB" value="1"/>
<property name="LARM_ELBOW.angle" value="0.0"/>
<property name="LARM_ELBOW.mode" value="HighGain"/>
<property name="LARM_ELBOW.NumOfAABB" value="1"/>
<property name="LARM_WRIST_Y.angle" value="0.0"/>
<property name="LARM_WRIST_Y.mode" value="HighGain"/>
<property name="LARM_WRIST_Y.NumOfAABB" value="1"/>
<property name="LARM_WRIST_P.angle" value="0.0"/>
<property name="LARM_WRIST_P.mode" value="HighGain"/>
<property name="LARM_WRIST_P.NumOfAABB" value="1"/>
<property name="LARM_WRIST_R.angle" value="0.0"/>
<property name="LARM_WRIST_R.mode" value="HighGain"/>
<property name="LARM_WRIST_R.NumOfAABB" value="1"/>
<property name="WAIST_P.angle" value="0.0"/>
<property name="WAIST_P.mode" value="HighGain"/>
<property name="WAIST_P.NumOfAABB" value="1"/>
<property name="WAIST_R.angle" value="0.0"/>
<property name="WAIST_R.mode" value="HighGain"/>
<property name="WAIST_R.NumOfAABB" value="1"/>
<property name="CHEST.angle" value="0.0"/>
<property name="CHEST.mode" value="HighGain"/>
<property name="CHEST.NumOfAABB" value="1"/>
</item>
<view class="com.generalrobotix.ui.view.GrxRobotHardwareClientView" name="RobotHardware RTC Client">
<property name="robotHost" value="localhost"/>
<property name="StateHolderRTC" value="StateHolder0"/>
<property name="interval" value="100"/>
<property name="RobotHardwareServiceRTC" value="RobotHardware0"/>
<property name="robotPort" value="2809"/>
<property name="ROBOT" value="SampleRobot"/>
</view>
<view class="com.generalrobotix.ui.view.Grx3DView" name="3DView">
<property name="view.mode" value="Room"/>
<property name="showCoM" value="false"/>
<property name="showCoMonFloor" value="false"/>
<property name="showDistance" value="false"/>
<property name="showIntersection" value="false"/>
<property name="eyeHomePosition" value="-0.70711 -0 0.70711 2 0.70711 -0 0.70711 2 0 1 0 0.8 0 0 0 1 "/>
<property name="showCollision" value="true"/>
<property name="showActualState" value="true"/>
<property name="showScale" value="true"/>
</view>
<item class="com.generalrobotix.ui.item.GrxRTSItem" name="longfloor" select="true">
<property name="longfloor(Robot)0.period" value="@CONTROLLER_TIME@"/>
<property name="HGcontroller0.period" value="@CONTROLLER_TIME@"/>
<property name="HGcontroller0.factory" value="HGcontroller"/>
<property name="connection" value="HGcontroller0.qOut:longfloor(Robot)0.qRef"/>
<property name="connection" value="HGcontroller0.dqOut:longfloor(Robot)0.dqRef"/>
<property name="connection" value="HGcontroller0.ddqOut:longfloor(Robot)0.ddqRef"/>
</item>
<item class="com.generalrobotix.ui.item.GrxModelItem" name="longfloor" url="@OPENHRP_DIR@/share/OpenHRP-3.1/sample/model/longfloor.wrl">
<property name="rtcName" value="longfloor(Robot)0"/>
<property name="inport" value="qRef:JOINT_VALUE"/>
<property name="inport" value="dqRef:JOINT_VELOCITY"/>
<property name="inport" value="ddqRef:JOINT_ACCELERATION"/>
<property name="outport" value="q:JOINT_VALUE"/>
<property name="outport" value="tau:JOINT_TORQUE"/>
<property name="WAIST.NumOfAABB" value="1"/>
<property name="WAIST.translation" value="0 0 -0.1"/>
<property name="WAIST.rotation" value="1 0 0 0"/>
</item>
<view class="com.generalrobotix.ui.view.GrxRobotHardwareClientView" name="RobotHardware RTC Client">
<property name="robotHost" value="localhost"/>
<property name="StateHolderRTC" value="StateHolder0"/>
<property name="interval" value="100"/>
<property name="RobotHardwareServiceRTC" value="RobotHardware0"/>
<property name="robotPort" value="2809"/>
<property name="ROBOT" value="longfloor"/>
</view>
<view class="com.generalrobotix.ui.view.Grx3DView" name="3DView">
<property name="view.mode" value="Room"/>
<property name="showCoM" value="false"/>
<property name="showCoMonFloor" value="false"/>
<property name="showDistance" value="false"/>
<property name="showIntersection" value="false"/>
<property name="eyeHomePosition" value="-0.70711 -0 0.70711 2 0.70711 -0 0.70711 2 0 1 0 0.8 0 0 0 1 "/>
<property name="showCollision" value="true"/>
<property name="showActualState" value="true"/>
<property name="showScale" value="true"/>
</view>
<item class="com.generalrobotix.ui.item.GrxCollisionPairItem" name="CP#longfloor_#sample1_">
<property name="springConstant" value="0 0 0 0 0 0"/>
<property name="slidingFriction" value="0.5"/>
<property name="jointName2" value=""/>
<property name="jointName1" value=""/>
<property name="damperConstant" value="0 0 0 0 0 0"/>
<property name="objectName2" value="longfloor"/>
<property name="objectName1" value="sample1"/>
<property name="springDamperModel" value="false"/>
<property name="staticFriction" value="0.5"/>
</item>
</mode>
</grxui>
102 changes: 102 additions & 0 deletions sample/SampleRobot/samplerobot_auto_balancer.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,102 @@
#!/usr/bin/env python

try:
from hrpsys.hrpsys_config import *
import OpenHRP
except:
print "import without hrpsys"
import rtm
from rtm import *
from OpenHRP import *
import waitInput
from waitInput import *
import socket
import time

def getRTCList ():
return [
['seq', "SequencePlayer"],
['sh', "StateHolder"],
['fk', "ForwardKinematics"],
['abc', "AutoBalancer"],
]

def init ():
global hcf
hcf = HrpsysConfigurator()
hcf.getRTCList = getRTCList
hcf.init ("SampleRobot(Robot)0")

def demo():
init()
# set initial pose from sample/controller/SampleController/etc/Sample.pos
initial_pose = [-7.779e-005, -0.378613, -0.000209793, 0.832038, -0.452564, 0.000244781, 0.31129, -0.159481, -0.115399, -0.636277, 0, 0, 0, -7.77902e-005, -0.378613, -0.000209794, 0.832038, -0.452564, 0.000244781, 0.31129, 0.159481, 0.115399, -0.636277, 0, 0, 0, 0, 0, 0]
arm_front_pose = [-7.779e-005, -0.378613, -0.000209793, 0.832038, -0.452564, 0.000244781, -0.8, -0.159481, -0.115399, -0.636277, 0, 0, 0, -7.77902e-005, -0.378613, -0.000209794, 0.832038, -0.452564, 0.000244781, -0.8, 0.159481, 0.115399, -0.636277, 0, 0, 0, 0.2, 0, 0]
hcf.seq_svc.setJointAngles(initial_pose, 2.0)
hcf.seq_svc.waitInterpolation()

# sample for AutoBalancer mode
# 1. AutoBalancer mode by fixing feet
hcf.abc_svc.startAutoBalancer([":rleg", ":lleg"]);
hcf.seq_svc.setJointAngles(arm_front_pose, 1.0)
hcf.seq_svc.waitInterpolation()
hcf.seq_svc.setJointAngles(initial_pose, 1.0)
hcf.seq_svc.waitInterpolation()
hcf.abc_svc.stopAutoBalancer();
# 2. AutoBalancer mode by fixing hands and feet
hcf.abc_svc.startAutoBalancer([":rleg", ":lleg", ":rarm", ":larm"])
hcf.seq_svc.setJointAngles(arm_front_pose, 1.0)
hcf.seq_svc.waitInterpolation()
hcf.seq_svc.setJointAngles(initial_pose, 1.0)
hcf.seq_svc.waitInterpolation()
hcf.abc_svc.stopAutoBalancer();
# 3. getAutoBalancerParam
ret = hcf.abc_svc.getAutoBalancerParam()
if ret[0]:
print "getAutoBalancerParam() => OK"
# 4. setAutoBalancerParam
ret[1].default_zmp_offsets = [[0.1,0,0], [0.1,0,0]]
hcf.abc_svc.setAutoBalancerParam(ret[1])
if ret[0] and ret[1].default_zmp_offsets == [[0.1,0,0], [0.1,0,0]]:
print "setAutoBalancerParam() => OK"
hcf.abc_svc.startAutoBalancer([":rleg", ":lleg"]);
hcf.abc_svc.stopAutoBalancer();
ret[1].default_zmp_offsets = [[0,0,0], [0,0,0]]
hcf.abc_svc.setAutoBalancerParam(ret[1])

# sample for walk pattern generation by AutoBalancer RTC
# 1. goPos
hcf.abc_svc.goPos(0.1, 0.05, 20)
hcf.abc_svc.waitFootSteps()
# 2. goVelocity and goStop
hcf.abc_svc.goVelocity(-0.1, -0.05, -20)
time.sleep(1)
hcf.abc_svc.goStop()
# 3. setFootSteps
hcf.abc_svc.setFootSteps([OpenHRP.AutoBalancerService.Footstep([0,-0.09,0], [1,0,0,0], ":rleg"), OpenHRP.AutoBalancerService.Footstep([0,0.09,0], [1,0,0,0], ":lleg")])
hcf.abc_svc.waitFootSteps()
hcf.abc_svc.setFootSteps([OpenHRP.AutoBalancerService.Footstep([0,-0.09,0], [1,0,0,0], ":rleg"), OpenHRP.AutoBalancerService.Footstep([0.15,0.09,0], [1,0,0,0], ":lleg"), OpenHRP.AutoBalancerService.Footstep([0.3,-0.09,0], [1,0,0,0], ":rleg"), OpenHRP.AutoBalancerService.Footstep([0.3,0.09,0], [1,0,0,0], ":lleg")])
hcf.abc_svc.waitFootSteps()
# 4. getGaitGeneratorParam
ret = hcf.abc_svc.getGaitGeneratorParam()
if ret[0]:
print "getGaitGeneratorParam() => OK"
# 5. setGaitGeneratorParam
ret[1].default_step_time = 0.7
ret[1].default_step_height = 0.15
ret[1].default_double_support_ratio = 0.4
hcf.abc_svc.setGaitGeneratorParam(ret[1])
ret = hcf.abc_svc.getGaitGeneratorParam()
if ret[0] and ret[1].default_step_time == 0.7 and ret[1].default_step_height == 0.15 and ret[1].default_double_support_ratio == 0.4:
print "setGaitGeneratorParam() => OK"
hcf.abc_svc.goVelocity(0,0,0)
time.sleep(1)
hcf.abc_svc.goStop()
# 6. walking by fixing
# abc_svc.startAutoBalancer([AutoBalancerService.AutoBalancerLimbParam(":rleg", [0,0,0], [0,0,0,0]),
# AutoBalancerService.AutoBalancerLimbParam(":lleg", [0,0,0], [0,0,0,0]),
# AutoBalancerService.AutoBalancerLimbParam(":rarm", [0,0,0], [0,0,0,0]),
# AutoBalancerService.AutoBalancerLimbParam(":larm", [0,0,0], [0,0,0,0])])
# abc_svc.goPos(0.1, 0.05, 20)
# abc_svc.waitFootSteps()
# abc_svc.stopABC()
43 changes: 43 additions & 0 deletions sample/SampleRobot/samplerobot_data_logger.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
#!/usr/bin/env python

try:
from hrpsys.hrpsys_config import *
import OpenHRP
except:
print "import without hrpsys"
import rtm
from rtm import *
from OpenHRP import *
import waitInput
from waitInput import *
import socket
import time

def getRTCList ():
return [
['seq', "SequencePlayer"],
['sh', "StateHolder"],
['fk', "ForwardKinematics"],
['log', "DataLogger"],
]

def init ():
global hcf
hcf = HrpsysConfigurator()
hcf.getRTCList = getRTCList
hcf.init ("SampleRobot(Robot)0")

def demo ():
init()
# set initial pose from sample/controller/SampleController/etc/Sample.pos
initial_pose = [-7.779e-005, -0.378613, -0.000209793, 0.832038, -0.452564, 0.000244781, 0.31129, -0.159481, -0.115399, -0.636277, 0, 0, 0, -7.77902e-005, -0.378613, -0.000209794, 0.832038, -0.452564, 0.000244781, 0.31129, 0.159481, 0.115399, -0.636277, 0, 0, 0, 0, 0, 0]

# Set max ring-buffer length : 200 [loop] * 0.002 [s] = 0.4 [s] data
hcf.log_svc.maxLength(200)
# Clear buffer
hcf.log_svc.clear()
hcf.seq_svc.setJointAngles(initial_pose, 2.0)
hcf.seq_svc.waitInterpolation()
# Save log files for each ports as /tmp/test-samplerobot-log.*
# file names are /tmp/test-samplerobot-log.[RTCName]_[PortName], c.f., /tmp/test-samplerobot-log.sh_qOut ... etc
hcf.log_svc.save("/tmp/test-samplerobot-log")
Loading