quadruped_ros2_control/descriptions/unitree/go1_description/config/ocs2/reference.info

47 lines
785 B
Plaintext

targetDisplacementVelocity 0.5;
targetRotationVelocity 1.57;
comHeight 0.33
defaultJointState
{
(0,0) -0.1 ; FL_hip_joint
(1,0) 0.8 ; FL_thigh_joint
(2,0) -1.44 ; FL_calf_joint
(3,0) 0.1 ; FR_hip_joint
(4,0) 0.8 ; FR_thigh_joint
(5,0) -1.44 ; FR_calf_joint
(6,0) -0.1 ; RL_hip_joint
(7,0) 0.8 ; RL_thigh_joint
(8,0) -1.44 ; RL_calf_joint
(9,0) 0.1 ; RR_hip_joint
(10,0) 0.8 ; RR_thigh_joint
(11,0) -1.44 ; RR_calf_joint
}
initialModeSchedule
{
modeSequence
{
[0] STANCE
[1] STANCE
}
eventTimes
{
[0] 0.5
}
}
defaultModeSequenceTemplate
{
modeSequence
{
[0] STANCE
}
switchingTimes
{
[0] 0.0
[1] 1.0
}
}