modified readme
This commit is contained in:
parent
b2f9f0e685
commit
4b8af1ab51
|
@ -18,6 +18,8 @@ Todo List:
|
|||
Video for Unitree Guide Controller:
|
||||
[![](http://i1.hdslb.com/bfs/archive/310e6208920985ac43015b2da31c01ec15e2c5f9.jpg)](https://www.bilibili.com/video/BV1aJbAeZEuo/)
|
||||
|
||||
Video for OCS2 Quadruped Controller:
|
||||
[![](http://i0.hdslb.com/bfs/archive/e758ce019587032449a153cf897a543443b64bba.jpg)](https://www.bilibili.com/video/BV1UcxieuEmH/)
|
||||
|
||||
|
||||
## Quick Start
|
||||
|
|
|
@ -3,6 +3,8 @@
|
|||
This is a ros2-control controller based on [legged_control](https://github.com/qiayuanl/legged_control)
|
||||
and [ocs2_ros2](https://github.com/legubiao/ocs2_ros2).
|
||||
|
||||
[![](http://i0.hdslb.com/bfs/archive/e758ce019587032449a153cf897a543443b64bba.jpg)](https://www.bilibili.com/video/BV1UcxieuEmH/)
|
||||
|
||||
## 2. Build
|
||||
|
||||
### 2.1 Build Dependencies
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
targetDisplacementVelocity 0.5;
|
||||
targetRotationVelocity 1.57;
|
||||
|
||||
comHeight 0.4
|
||||
comHeight 0.39
|
||||
|
||||
defaultJointState
|
||||
{
|
||||
|
|
|
@ -154,7 +154,7 @@ initialState
|
|||
;; Base Pose: [position, orientation] ;;
|
||||
(6,0) 0.0 ; p_base_x
|
||||
(7,0) 0.0 ; p_base_y
|
||||
(8,0) 0.3 ; p_base_z
|
||||
(8,0) 0.39 ; p_base_z
|
||||
(9,0) 0.0 ; theta_base_z
|
||||
(10,0) 0.0 ; theta_base_y
|
||||
(11,0) 0.0 ; theta_base_x
|
||||
|
@ -283,9 +283,9 @@ selfCollision
|
|||
; Whole body control
|
||||
torqueLimitsTask
|
||||
{
|
||||
(0,0) 12.0 ; HAA
|
||||
(1,0) 12.0 ; HFE
|
||||
(2,0) 12.0 ; KFE
|
||||
(0,0) 35.278 ; HAA
|
||||
(1,0) 35.278 ; HFE
|
||||
(2,0) 44.4 ; KFE
|
||||
}
|
||||
|
||||
frictionConeTask
|
||||
|
|
|
@ -74,6 +74,7 @@ unitree_guide_controller:
|
|||
ocs2_quadruped_controller:
|
||||
ros__parameters:
|
||||
update_rate: 500 # Hz
|
||||
default_kd: 5.0
|
||||
|
||||
joints:
|
||||
- FL_hip_joint
|
||||
|
|
|
@ -1,21 +1,21 @@
|
|||
targetDisplacementVelocity 0.5;
|
||||
targetRotationVelocity 1.57;
|
||||
|
||||
comHeight 0.307
|
||||
comHeight 0.33
|
||||
|
||||
defaultJointState
|
||||
{
|
||||
(0,0) -0.20 ; FL_hip_joint
|
||||
(1,0) 0.7 ; FL_thigh_joint
|
||||
(0,0) -0.1 ; FL_hip_joint
|
||||
(1,0) 0.8 ; FL_thigh_joint
|
||||
(2,0) -1.44 ; FL_calf_joint
|
||||
(3,0) 0.20 ; FR_hip_joint
|
||||
(4,0) 0.7 ; FR_thigh_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.20 ; RL_hip_joint
|
||||
(7,0) 0.7 ; RL_thigh_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.20 ; RR_hip_joint
|
||||
(10,0) 0.7 ; RR_thigh_joint
|
||||
(9,0) 0.1 ; RR_hip_joint
|
||||
(10,0) 0.8 ; RR_thigh_joint
|
||||
(11,0) -1.44 ; RR_calf_joint
|
||||
}
|
||||
|
||||
|
|
|
@ -19,7 +19,7 @@ swing_trajectory_config
|
|||
{
|
||||
liftOffVelocity 0.05
|
||||
touchDownVelocity -0.1
|
||||
swingHeight 0.08
|
||||
swingHeight 0.1
|
||||
swingTimeScale 0.15
|
||||
}
|
||||
|
||||
|
@ -154,7 +154,7 @@ initialState
|
|||
;; Base Pose: [position, orientation] ;;
|
||||
(6,0) 0.0 ; p_base_x
|
||||
(7,0) 0.0 ; p_base_y
|
||||
(8,0) 0.3 ; p_base_z
|
||||
(8,0) 0.33 ; p_base_z
|
||||
(9,0) 0.0 ; theta_base_z
|
||||
(10,0) 0.0 ; theta_base_y
|
||||
(11,0) 0.0 ; theta_base_x
|
||||
|
@ -283,9 +283,9 @@ selfCollision
|
|||
; Whole body control
|
||||
torqueLimitsTask
|
||||
{
|
||||
(0,0) 33.5 ; HAA
|
||||
(1,0) 33.5 ; HFE
|
||||
(2,0) 33.5 ; KFE
|
||||
(0,0) 23.7 ; HAA
|
||||
(1,0) 23.7 ; HFE
|
||||
(2,0) 35.5 ; KFE
|
||||
}
|
||||
|
||||
frictionConeTask
|
||||
|
|
|
@ -1,20 +1,20 @@
|
|||
targetDisplacementVelocity 0.5;
|
||||
targetDisplacementVelocity 0.45;
|
||||
targetRotationVelocity 1.57;
|
||||
|
||||
comHeight 0.29
|
||||
comHeight 0.3
|
||||
|
||||
defaultJointState
|
||||
{
|
||||
(0,0) -0.10 ; FL_hip_joint
|
||||
(0,0) -0.20 ; FL_hip_joint
|
||||
(1,0) 0.72 ; FL_thigh_joint
|
||||
(2,0) -1.44 ; FL_calf_joint
|
||||
(3,0) 0.10 ; FR_hip_joint
|
||||
(3,0) 0.20 ; FR_hip_joint
|
||||
(4,0) 0.72 ; FR_thigh_joint
|
||||
(5,0) -1.44 ; FR_calf_joint
|
||||
(6,0) -0.10 ; RL_hip_joint
|
||||
(6,0) -0.20 ; RL_hip_joint
|
||||
(7,0) 0.72 ; RL_thigh_joint
|
||||
(8,0) -1.44 ; RL_calf_joint
|
||||
(9,0) 0.10 ; RR_hip_joint
|
||||
(9,0) 0.20 ; RR_hip_joint
|
||||
(10,0) 0.72 ; RR_thigh_joint
|
||||
(11,0) -1.44 ; RR_calf_joint
|
||||
}
|
||||
|
|
|
@ -283,9 +283,9 @@ selfCollision
|
|||
; Whole body control
|
||||
torqueLimitsTask
|
||||
{
|
||||
(0,0) 33.5 ; HAA
|
||||
(1,0) 33.5 ; HFE
|
||||
(2,0) 33.5 ; KFE
|
||||
(0,0) 23.7 ; HAA
|
||||
(1,0) 23.7 ; HFE
|
||||
(2,0) 35.5 ; KFE
|
||||
}
|
||||
|
||||
frictionConeTask
|
||||
|
|
File diff suppressed because it is too large
Load Diff
Loading…
Reference in New Issue