Skip to content

Commit

Permalink
add HRP2JSK HRP2JSKNT HRP2JSKNTS
Browse files Browse the repository at this point in the history
  • Loading branch information
Naoki-Hiraoka committed Apr 23, 2020
1 parent f419d1c commit 5332aa9
Show file tree
Hide file tree
Showing 15 changed files with 1,955 additions and 30 deletions.
11 changes: 11 additions & 0 deletions hrpsys_choreonoid/config/HRP2JSKCustomizer.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
bush:
springT: 3.3e5
dampingT: 3.3e2
springR: 2.5e3
dampingR: 2.5

tilt_laser:
TILT_UPPER_BOUND: 1.35
TILT_POSITIVE_SPEED: 1.0
TILT_LOWER_BOUND: -0.7
TILT_NEGATIVE_SPEED: -1.0
11 changes: 11 additions & 0 deletions hrpsys_choreonoid/config/HRP2JSKNTCustomizer.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
bush:
springT: 3.3e5
dampingT: 3.3e2
springR: 2.5e3
dampingR: 2.5

tilt_laser:
TILT_UPPER_BOUND: 1.35
TILT_POSITIVE_SPEED: 1.0
TILT_LOWER_BOUND: -0.7
TILT_NEGATIVE_SPEED: -1.0
11 changes: 11 additions & 0 deletions hrpsys_choreonoid/config/HRP2JSKNTSCustomizer.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
bush:
springT: 3.3e5
dampingT: 3.3e2
springR: 2.5e3
dampingR: 2.5

tilt_laser:
TILT_UPPER_BOUND: 1.35
TILT_POSITIVE_SPEED: 1.0
TILT_LOWER_BOUND: -0.7
TILT_NEGATIVE_SPEED: -1.0
66 changes: 36 additions & 30 deletions hrpsys_choreonoid/src/JAXONCustomizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

#include <cmath>
#include <cstring>
#include <string>
#include <fstream>
#include <boost/function.hpp>
#include <boost/bind.hpp>
Expand Down Expand Up @@ -53,6 +54,7 @@ static BodyCustomizerInterface bodyCustomizerInterface;

struct JointValSet
{
int index;
double* valuePtr;
double* velocityPtr;
double* torqueForcePtr;
Expand All @@ -63,7 +65,7 @@ struct JAXONCustomizer
BodyHandle bodyHandle;

bool hasVirtualBushJoints;
JointValSet jointValSets[2][3];
JointValSet jointValSets[4][6];
double springT;
double dampingT;
double springR;
Expand Down Expand Up @@ -102,28 +104,26 @@ static const char** getTargetModelNames()

static void getVirtualbushJoints(JAXONCustomizer* customizer, BodyHandle body)
{
customizer->hasVirtualBushJoints = true;

int bushIndices[2][3];

bushIndices[0][0] = bodyInterface->getLinkIndexFromName(body, "RLEG_BUSH_Z");
bushIndices[0][1] = bodyInterface->getLinkIndexFromName(body, "RLEG_BUSH_ROLL");
bushIndices[0][2] = bodyInterface->getLinkIndexFromName(body, "RLEG_BUSH_PITCH");
bushIndices[1][0] = bodyInterface->getLinkIndexFromName(body, "LLEG_BUSH_Z");
bushIndices[1][1] = bodyInterface->getLinkIndexFromName(body, "LLEG_BUSH_ROLL");
bushIndices[1][2] = bodyInterface->getLinkIndexFromName(body, "LLEG_BUSH_PITCH");

for(int i=0; i < 2; ++i){
for(int j=0; j < 3; ++j){
int bushIndex = bushIndices[i][j];
if(bushIndex < 0){
std::cerr << "[Customizer] failed to find out : " << i << " " << j << std::endl;
customizer->hasVirtualBushJoints = false;
} else {
JointValSet& jointValSet = customizer->jointValSets[i][j];
jointValSet.valuePtr = bodyInterface->getJointValuePtr(body, bushIndex);
jointValSet.velocityPtr = bodyInterface->getJointVelocityPtr(body, bushIndex);
jointValSet.torqueForcePtr = bodyInterface->getJointForcePtr(body, bushIndex);
customizer->hasVirtualBushJoints = false;

static const char* limbs[] = {"RLEG", "LLEG", "RARM", "LARM"};
static const char* types[] = {"X", "Y", "Z", "ROLL", "PITCH", "YAW"};
char bush_name[30];

for(int i=0; i < 4; ++i){
for(int j=0; j < 6; ++j){
JointValSet& jointValSet = customizer->jointValSets[i][j];
sprintf(bush_name, "%s_BUSH_%s", limbs[i], types[j]);
jointValSet.index = bodyInterface->getLinkIndexFromName(body, bush_name);
if(jointValSet.index < 0){
std::cerr << "[Customizer] failed to find out : " << bush_name << std::endl;
}else{
std::cerr << "[Customizer] find out : " << bush_name << std::endl;
customizer->hasVirtualBushJoints = true;

jointValSet.valuePtr = bodyInterface->getJointValuePtr(body, jointValSet.index);
jointValSet.velocityPtr = bodyInterface->getJointVelocityPtr(body, jointValSet.index);
jointValSet.torqueForcePtr = bodyInterface->getJointForcePtr(body, jointValSet.index);
}
}
}
Expand Down Expand Up @@ -215,15 +215,21 @@ static void setVirtualJointForces(BodyCustomizerHandle customizerHandle)
JAXONCustomizer* customizer = static_cast<JAXONCustomizer*>(customizerHandle);

if(customizer->hasVirtualBushJoints){
for(int i=0; i < 2; ++i){
JointValSet& trans = customizer->jointValSets[i][0];
*(trans.torqueForcePtr) = - customizer->springT * (*trans.valuePtr) - customizer->dampingT * (*trans.velocityPtr);
//std::cerr << i << " " << 0 << " " << *(trans.torqueForcePtr) << " = " << -customizer->springT << " x " << *trans.valuePtr << " + " << - customizer->dampingT << " x " << *trans.velocityPtr << std::endl;
for(int i=0; i < 4; ++i){
for(int j=0; j < 3; ++j){
JointValSet& trans = customizer->jointValSets[i][j];
if(trans.index >= 0){
*(trans.torqueForcePtr) = - customizer->springT * (*trans.valuePtr) - customizer->dampingT * (*trans.velocityPtr);
//std::cerr << i << " " << 0 << " " << *(trans.torqueForcePtr) << " = " << -customizer->springT << " x " << *trans.valuePtr << " + " << - customizer->dampingT << " x " << *trans.velocityPtr << std::endl;
}
}

for(int j=1; j < 3; ++j){
for(int j=3; j < 6; ++j){
JointValSet& rot = customizer->jointValSets[i][j];
*(rot.torqueForcePtr) = - customizer->springR * (*rot.valuePtr) - customizer->dampingR * (*rot.velocityPtr);
//std::cerr << i << " " << j << " " << *(rot.torqueForcePtr) << " = " << -customizer->springR << " x " << *rot.valuePtr << " + " << - customizer->dampingR << " x " << *rot.velocityPtr << std::endl;
if(rot.index >= 0){
*(rot.torqueForcePtr) = - customizer->springR * (*rot.valuePtr) - customizer->dampingR * (*rot.velocityPtr);
//std::cerr << i << " " << j << " " << *(rot.torqueForcePtr) << " = " << -customizer->springR << " x " << *rot.valuePtr << " + " << - customizer->dampingR << " x " << *rot.velocityPtr << std::endl;
}
}
}
}
Expand Down
29 changes: 29 additions & 0 deletions hrpsys_choreonoid_tutorials/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,14 @@ else()
set (JSK_MODELS_DIR ${jsk_models_SOURCE_PREFIX})
endif()

find_package(hrp2_models QUIET)
if(NOT "${hrp2_models_FOUND}")
string(ASCII 27 Esc)
message(WARNING "${Esc}[1;33mPackage hrp2_models is not found, if you have right to access them please include source code in catkin workspace${Esc}[m")
else()
set (HRP2_MODELS_DIR ${hrp2_models_SOURCE_PREFIX})
endif()

################################
## compile_openhrp_model
## Generate OpenHRP3 .xml and .conf file.
Expand Down Expand Up @@ -189,6 +197,27 @@ if (${jsk_models_FOUND})
configure_file(${PROJECT_SOURCE_DIR}/config/CHIDORI_RH_FLAT.cnoid.in ${PROJECT_SOURCE_DIR}/config/CHIDORI_RH_FLAT.cnoid @ONLY)
endif()

###
#HRP2JSK conid
###
if (${hrp2_models_FOUND})
configure_file(${PROJECT_SOURCE_DIR}/config/HRP2JSK_RH_FLAT.cnoid.in ${PROJECT_SOURCE_DIR}/config/HRP2JSK_RH_FLAT.cnoid @ONLY)
endif()

###
#HRP2JSKNT conid
###
if (${hrp2_models_FOUND})
configure_file(${PROJECT_SOURCE_DIR}/config/HRP2JSKNT_RH_FLAT.cnoid.in ${PROJECT_SOURCE_DIR}/config/HRP2JSKNT_RH_FLAT.cnoid @ONLY)
endif()

###
#HRP2JSKNTS conid
###
if (${hrp2_models_FOUND})
configure_file(${PROJECT_SOURCE_DIR}/config/HRP2JSKNTS_RH_FLAT.cnoid.in ${PROJECT_SOURCE_DIR}/config/HRP2JSKNTS_RH_FLAT.cnoid @ONLY)
endif()

###
# scene.yaml
###
Expand Down
92 changes: 92 additions & 0 deletions hrpsys_choreonoid_tutorials/config/BodyRTC_HRP2JSK.RH.conf
Original file line number Diff line number Diff line change
@@ -0,0 +1,92 @@
##
name-server = localhost:15005
##
## PD Controller
## in: angleRef, angle
## out: torque
##
in-port = tauIn:JOINT_TORQUE
out-port = angleOut:JOINT_VALUE
out-port = qvel:JOINT_VELOCITY
out-port = torque:JOINT_TORQUE
# out-port = ddq:JOINT_ACCELERATION
connection = tauIn:RobotHardware_choreonoid0:torqueOut
connection = angleOut:RobotHardware_choreonoid0:angleIn
connection = qvel:RobotHardware_choreonoid0:qvel_sim
connection = torque:RobotHardware_choreonoid0:torque_sim
###
# debug ## ground truth robot potition
###
out-port = WAIST:WAIST:ABS_TRANSFORM
# out-port = headq:motor_joint:JOINT_VALUE
####
# sensors
####
out-port = rfsensor_sim:rfsensor:FORCE_SENSOR
out-port = lfsensor_sim:lfsensor:FORCE_SENSOR
out-port = rhsensor_sim:rhsensor:FORCE_SENSOR
out-port = lhsensor_sim:lhsensor:FORCE_SENSOR
out-port = gsensor_sim:gsensor:ACCELERATION_SENSOR2
out-port = gyrometer_sim:gyrometer:RATE_GYRO_SENSOR2
connection = rfsensor_sim:RobotHardware_choreonoid0:rfsensor_sim
connection = lfsensor_sim:RobotHardware_choreonoid0:lfsensor_sim
connection = rhsensor_sim:RobotHardware_choreonoid0:rhsensor_sim
connection = lhsensor_sim:RobotHardware_choreonoid0:lhsensor_sim
connection = gsensor_sim:RobotHardware_choreonoid0:gsensor_sim
connection = gyrometer_sim:RobotHardware_choreonoid0:gyrometer_sim
####
# vision
####
# out-port = HEAD_RANGE:HEAD_RANGE:RANGE_SENSOR
# out-port = HEAD_LEFT_DEPTH:HEAD_LEFT_CAMERA:CAMERA_RANGE
# out-port = HEAD_LEFT_CAMERA:HEAD_LEFT_CAMERA:CAMERA_IMAGE
# out-port = HEAD_RIGHT_CAMERA:HEAD_RIGHT_CAMERA:CAMERA_IMAGE
#out-port = CHEST_CAMERA:CHEST_CAMERA:CAMERA_IMAGE
#out-port = LARM_CAMERA:LARM_CAMERA:CAMERA_IMAGE
#out-port = RARM_CAMERA:RARM_CAMERA:CAMERA_IMAGE
#out-port = LARM_CAMERA_N:LARM_CAMERA_N:CAMERA_IMAGE
#out-port = RARM_CAMERA_N:RARM_CAMERA_N:CAMERA_IMAGE

####
# constraint
####
# out-port = F_BODY:WAIST:CONSTRAINT_FORCE
# out-port = F_CHEST_LINK0:CHEST_JOINT0:CONSTRAINT_FORCE
# out-port = F_CHEST_LINK1:CHEST_JOINT1:CONSTRAINT_FORCE
# out-port = F_CHEST_LINK2:CHEST_JOINT2:CONSTRAINT_FORCE
# out-port = F_HEAD_LINK0:HEAD_JOINT0:CONSTRAINT_FORCE
# out-port = F_HEAD_LINK1:HEAD_JOINT1:CONSTRAINT_FORCE
# out-port = F_LARM_LINK0:LARM_JOINT0:CONSTRAINT_FORCE
# out-port = F_LARM_LINK1:LARM_JOINT1:CONSTRAINT_FORCE
# out-port = F_LARM_LINK2:LARM_JOINT2:CONSTRAINT_FORCE
# out-port = F_LARM_LINK3:LARM_JOINT3:CONSTRAINT_FORCE
# out-port = F_LARM_LINK4:LARM_JOINT4:CONSTRAINT_FORCE
# out-port = F_LARM_LINK5:LARM_JOINT5:CONSTRAINT_FORCE
# out-port = F_LARM_LINK6:LARM_JOINT6:CONSTRAINT_FORCE
# out-port = F_LARM_LINK7:LARM_JOINT7:CONSTRAINT_FORCE
# out-port = F_LARM_FINGER0:LARM_F_JOINT0:CONSTRAINT_FORCE
# out-port = F_LARM_FINGER1:LARM_F_JOINT1:CONSTRAINT_FORCE
# out-port = F_RARM_LINK0:RARM_JOINT0:CONSTRAINT_FORCE
# out-port = F_RARM_LINK1:RARM_JOINT1:CONSTRAINT_FORCE
# out-port = F_RARM_LINK2:RARM_JOINT2:CONSTRAINT_FORCE
# out-port = F_RARM_LINK3:RARM_JOINT3:CONSTRAINT_FORCE
# out-port = F_RARM_LINK4:RARM_JOINT4:CONSTRAINT_FORCE
# out-port = F_RARM_LINK5:RARM_JOINT5:CONSTRAINT_FORCE
# out-port = F_RARM_LINK6:RARM_JOINT6:CONSTRAINT_FORCE
# out-port = F_RARM_LINK7:RARM_JOINT7:CONSTRAINT_FORCE
# out-port = F_RARM_FINGER0:RARM_F_JOINT0:CONSTRAINT_FORCE
# out-port = F_RARM_FINGER1:RARM_F_JOINT1:CONSTRAINT_FORCE
# out-port = F_LLEG_LINK0:LLEG_JOINT0:CONSTRAINT_FORCE
# out-port = F_LLEG_LINK1:LLEG_JOINT1:CONSTRAINT_FORCE
# out-port = F_LLEG_LINK2:LLEG_JOINT2:CONSTRAINT_FORCE
# out-port = F_LLEG_LINK3:LLEG_JOINT3:CONSTRAINT_FORCE
# out-port = F_LLEG_LINK4:LLEG_JOINT4:CONSTRAINT_FORCE
# out-port = F_LLEG_LINK5_UPPER:LLEG_JOINT5:CONSTRAINT_FORCE
# out-port = F_LLEG_LINK5_LOWER:LLEG_BUSH_PITCH:CONSTRAINT_FORCE
# out-port = F_RLEG_LINK0:RLEG_JOINT0:CONSTRAINT_FORCE
# out-port = F_RLEG_LINK1:RLEG_JOINT1:CONSTRAINT_FORCE
# out-port = F_RLEG_LINK2:RLEG_JOINT2:CONSTRAINT_FORCE
# out-port = F_RLEG_LINK3:RLEG_JOINT3:CONSTRAINT_FORCE
# out-port = F_RLEG_LINK4:RLEG_JOINT4:CONSTRAINT_FORCE
# out-port = F_RLEG_LINK5_UPPER:RLEG_JOINT5:CONSTRAINT_FORCE
# out-port = F_RLEG_LINK5_LOWER:RLEG_BUSH_PITCH:CONSTRAINT_FORCE
92 changes: 92 additions & 0 deletions hrpsys_choreonoid_tutorials/config/BodyRTC_HRP2JSKNT.RH.conf
Original file line number Diff line number Diff line change
@@ -0,0 +1,92 @@
##
name-server = localhost:15005
##
## PD Controller
## in: angleRef, angle
## out: torque
##
in-port = tauIn:RLEG_JOINT0,RLEG_JOINT1,RLEG_JOINT2,RLEG_JOINT3,RLEG_JOINT4,RLEG_JOINT5,RLEG_JOINT6,LLEG_JOINT0,LLEG_JOINT1,LLEG_JOINT2,LLEG_JOINT3,LLEG_JOINT4,LLEG_JOINT5,LLEG_JOINT6,CHEST_JOINT0,CHEST_JOINT1,HEAD_JOINT0,HEAD_JOINT1,RARM_JOINT0,RARM_JOINT1,RARM_JOINT2,RARM_JOINT3,RARM_JOINT4,RARM_JOINT5,RARM_JOINT6,RARM_JOINT7,LARM_JOINT0,LARM_JOINT1,LARM_JOINT2,LARM_JOINT3,LARM_JOINT4,LARM_JOINT5,LARM_JOINT6,LARM_JOINT7:JOINT_TORQUE
out-port = angleOut:RLEG_JOINT0,RLEG_JOINT1,RLEG_JOINT2,RLEG_JOINT3,RLEG_JOINT4,RLEG_JOINT5,RLEG_JOINT6,LLEG_JOINT0,LLEG_JOINT1,LLEG_JOINT2,LLEG_JOINT3,LLEG_JOINT4,LLEG_JOINT5,LLEG_JOINT6,CHEST_JOINT0,CHEST_JOINT1,HEAD_JOINT0,HEAD_JOINT1,RARM_JOINT0,RARM_JOINT1,RARM_JOINT2,RARM_JOINT3,RARM_JOINT4,RARM_JOINT5,RARM_JOINT6,RARM_JOINT7,LARM_JOINT0,LARM_JOINT1,LARM_JOINT2,LARM_JOINT3,LARM_JOINT4,LARM_JOINT5,LARM_JOINT6,LARM_JOINT7:JOINT_VALUE
out-port = qvel:RLEG_JOINT0,RLEG_JOINT1,RLEG_JOINT2,RLEG_JOINT3,RLEG_JOINT4,RLEG_JOINT5,RLEG_JOINT6,LLEG_JOINT0,LLEG_JOINT1,LLEG_JOINT2,LLEG_JOINT3,LLEG_JOINT4,LLEG_JOINT5,LLEG_JOINT6,CHEST_JOINT0,CHEST_JOINT1,HEAD_JOINT0,HEAD_JOINT1,RARM_JOINT0,RARM_JOINT1,RARM_JOINT2,RARM_JOINT3,RARM_JOINT4,RARM_JOINT5,RARM_JOINT6,RARM_JOINT7,LARM_JOINT0,LARM_JOINT1,LARM_JOINT2,LARM_JOINT3,LARM_JOINT4,LARM_JOINT5,LARM_JOINT6,LARM_JOINT7:JOINT_VELOCITY
out-port = torque:RLEG_JOINT0,RLEG_JOINT1,RLEG_JOINT2,RLEG_JOINT3,RLEG_JOINT4,RLEG_JOINT5,RLEG_JOINT6,LLEG_JOINT0,LLEG_JOINT1,LLEG_JOINT2,LLEG_JOINT3,LLEG_JOINT4,LLEG_JOINT5,LLEG_JOINT6,CHEST_JOINT0,CHEST_JOINT1,HEAD_JOINT0,HEAD_JOINT1,RARM_JOINT0,RARM_JOINT1,RARM_JOINT2,RARM_JOINT3,RARM_JOINT4,RARM_JOINT5,RARM_JOINT6,RARM_JOINT7,LARM_JOINT0,LARM_JOINT1,LARM_JOINT2,LARM_JOINT3,LARM_JOINT4,LARM_JOINT5,LARM_JOINT6,LARM_JOINT7:JOINT_TORQUE
# out-port = ddq:JOINT_ACCELERATION
connection = tauIn:RobotHardware_choreonoid0:torqueOut
connection = angleOut:RobotHardware_choreonoid0:angleIn
connection = qvel:RobotHardware_choreonoid0:qvel_sim
connection = torque:RobotHardware_choreonoid0:torque_sim
###
# debug ## ground truth robot potition
###
out-port = WAIST:WAIST:ABS_TRANSFORM
# out-port = headq:motor_joint:JOINT_VALUE
####
# sensors
####
out-port = rfsensor_sim:rfsensor:FORCE_SENSOR
out-port = lfsensor_sim:lfsensor:FORCE_SENSOR
out-port = rhsensor_sim:rhsensor:FORCE_SENSOR
out-port = lhsensor_sim:lhsensor:FORCE_SENSOR
out-port = gsensor_sim:gsensor:ACCELERATION_SENSOR2
out-port = gyrometer_sim:gyrometer:RATE_GYRO_SENSOR2
connection = rfsensor_sim:RobotHardware_choreonoid0:rfsensor_sim
connection = lfsensor_sim:RobotHardware_choreonoid0:lfsensor_sim
connection = rhsensor_sim:RobotHardware_choreonoid0:rhsensor_sim
connection = lhsensor_sim:RobotHardware_choreonoid0:lhsensor_sim
connection = gsensor_sim:RobotHardware_choreonoid0:gsensor_sim
connection = gyrometer_sim:RobotHardware_choreonoid0:gyrometer_sim
####
# vision
####
# out-port = HEAD_RANGE:HEAD_RANGE:RANGE_SENSOR
# out-port = HEAD_LEFT_DEPTH:HEAD_LEFT_CAMERA:CAMERA_RANGE
# out-port = HEAD_LEFT_CAMERA:HEAD_LEFT_CAMERA:CAMERA_IMAGE
# out-port = HEAD_RIGHT_CAMERA:HEAD_RIGHT_CAMERA:CAMERA_IMAGE
#out-port = CHEST_CAMERA:CHEST_CAMERA:CAMERA_IMAGE
#out-port = LARM_CAMERA:LARM_CAMERA:CAMERA_IMAGE
#out-port = RARM_CAMERA:RARM_CAMERA:CAMERA_IMAGE
#out-port = LARM_CAMERA_N:LARM_CAMERA_N:CAMERA_IMAGE
#out-port = RARM_CAMERA_N:RARM_CAMERA_N:CAMERA_IMAGE

####
# constraint
####
# out-port = F_BODY:WAIST:CONSTRAINT_FORCE
# out-port = F_CHEST_LINK0:CHEST_JOINT0:CONSTRAINT_FORCE
# out-port = F_CHEST_LINK1:CHEST_JOINT1:CONSTRAINT_FORCE
# out-port = F_CHEST_LINK2:CHEST_JOINT2:CONSTRAINT_FORCE
# out-port = F_HEAD_LINK0:HEAD_JOINT0:CONSTRAINT_FORCE
# out-port = F_HEAD_LINK1:HEAD_JOINT1:CONSTRAINT_FORCE
# out-port = F_LARM_LINK0:LARM_JOINT0:CONSTRAINT_FORCE
# out-port = F_LARM_LINK1:LARM_JOINT1:CONSTRAINT_FORCE
# out-port = F_LARM_LINK2:LARM_JOINT2:CONSTRAINT_FORCE
# out-port = F_LARM_LINK3:LARM_JOINT3:CONSTRAINT_FORCE
# out-port = F_LARM_LINK4:LARM_JOINT4:CONSTRAINT_FORCE
# out-port = F_LARM_LINK5:LARM_JOINT5:CONSTRAINT_FORCE
# out-port = F_LARM_LINK6:LARM_JOINT6:CONSTRAINT_FORCE
# out-port = F_LARM_LINK7:LARM_JOINT7:CONSTRAINT_FORCE
# out-port = F_LARM_FINGER0:LARM_F_JOINT0:CONSTRAINT_FORCE
# out-port = F_LARM_FINGER1:LARM_F_JOINT1:CONSTRAINT_FORCE
# out-port = F_RARM_LINK0:RARM_JOINT0:CONSTRAINT_FORCE
# out-port = F_RARM_LINK1:RARM_JOINT1:CONSTRAINT_FORCE
# out-port = F_RARM_LINK2:RARM_JOINT2:CONSTRAINT_FORCE
# out-port = F_RARM_LINK3:RARM_JOINT3:CONSTRAINT_FORCE
# out-port = F_RARM_LINK4:RARM_JOINT4:CONSTRAINT_FORCE
# out-port = F_RARM_LINK5:RARM_JOINT5:CONSTRAINT_FORCE
# out-port = F_RARM_LINK6:RARM_JOINT6:CONSTRAINT_FORCE
# out-port = F_RARM_LINK7:RARM_JOINT7:CONSTRAINT_FORCE
# out-port = F_RARM_FINGER0:RARM_F_JOINT0:CONSTRAINT_FORCE
# out-port = F_RARM_FINGER1:RARM_F_JOINT1:CONSTRAINT_FORCE
# out-port = F_LLEG_LINK0:LLEG_JOINT0:CONSTRAINT_FORCE
# out-port = F_LLEG_LINK1:LLEG_JOINT1:CONSTRAINT_FORCE
# out-port = F_LLEG_LINK2:LLEG_JOINT2:CONSTRAINT_FORCE
# out-port = F_LLEG_LINK3:LLEG_JOINT3:CONSTRAINT_FORCE
# out-port = F_LLEG_LINK4:LLEG_JOINT4:CONSTRAINT_FORCE
# out-port = F_LLEG_LINK5_UPPER:LLEG_JOINT5:CONSTRAINT_FORCE
# out-port = F_LLEG_LINK5_LOWER:LLEG_BUSH_PITCH:CONSTRAINT_FORCE
# out-port = F_RLEG_LINK0:RLEG_JOINT0:CONSTRAINT_FORCE
# out-port = F_RLEG_LINK1:RLEG_JOINT1:CONSTRAINT_FORCE
# out-port = F_RLEG_LINK2:RLEG_JOINT2:CONSTRAINT_FORCE
# out-port = F_RLEG_LINK3:RLEG_JOINT3:CONSTRAINT_FORCE
# out-port = F_RLEG_LINK4:RLEG_JOINT4:CONSTRAINT_FORCE
# out-port = F_RLEG_LINK5_UPPER:RLEG_JOINT5:CONSTRAINT_FORCE
# out-port = F_RLEG_LINK5_LOWER:RLEG_BUSH_PITCH:CONSTRAINT_FORCE
Loading

0 comments on commit 5332aa9

Please sign in to comment.