add support for unitree A1 simulation
This commit is contained in:
parent
4b8af1ab51
commit
86bbcf75e6
Binary file not shown.
After Width: | Height: | Size: 50 KiB |
|
@ -5,6 +5,7 @@ This folder contains the URDF and SRDF files for the quadruped robot.
|
|||
* Unitree
|
||||
* [Go1](unitree/go1_description/)
|
||||
* [Go2](unitree/go2_description/)
|
||||
* [A1](unitree/a1_description/)
|
||||
* [Aliengo](unitree/aliengo_description/)
|
||||
* [B2](unitree/b2_description/)
|
||||
* Xiaomi
|
||||
|
|
|
@ -0,0 +1,11 @@
|
|||
cmake_minimum_required(VERSION 3.8)
|
||||
project(a1_description)
|
||||
|
||||
find_package(ament_cmake REQUIRED)
|
||||
|
||||
install(
|
||||
DIRECTORY meshes xacro launch config urdf
|
||||
DESTINATION share/${PROJECT_NAME}/
|
||||
)
|
||||
|
||||
ament_package()
|
|
@ -0,0 +1,34 @@
|
|||
# Unitree A1 Description
|
||||
This repository contains the urdf model of A1.
|
||||
|
||||
![Aliengo](../../../.images/a1.png)
|
||||
|
||||
Tested environment:
|
||||
* Ubuntu 24.04
|
||||
* ROS2 Jazzy
|
||||
|
||||
## Build
|
||||
```bash
|
||||
cd ~/ros2_ws
|
||||
colcon build --packages-up-to a1_description
|
||||
```
|
||||
|
||||
## Visualize the robot
|
||||
To visualize and check the configuration of the robot in rviz, simply launch:
|
||||
```bash
|
||||
source ~/ros2_ws/install/setup.bash
|
||||
ros2 launch a1_description visualize.launch.py
|
||||
```
|
||||
|
||||
## Launch ROS2 Control
|
||||
* Unitree Guide Controller
|
||||
```bash
|
||||
source ~/ros2_ws/install/setup.bash
|
||||
ros2 launch a1_description unitree_guide.launch.py
|
||||
```
|
||||
* OCS2 Quadruped Controller
|
||||
```bash
|
||||
source ~/ros2_ws/install/setup.bash
|
||||
ros2 launch a1_description ocs2_control.launch.py
|
||||
```
|
||||
|
|
@ -0,0 +1,255 @@
|
|||
list
|
||||
{
|
||||
[0] stance
|
||||
[1] trot
|
||||
[2] standing_trot
|
||||
[3] flying_trot
|
||||
[4] pace
|
||||
[5] standing_pace
|
||||
[6] dynamic_walk
|
||||
[7] static_walk
|
||||
[8] amble
|
||||
[9] lindyhop
|
||||
[10] skipping
|
||||
[11] pawup
|
||||
}
|
||||
|
||||
stance
|
||||
{
|
||||
modeSequence
|
||||
{
|
||||
[0] STANCE
|
||||
}
|
||||
switchingTimes
|
||||
{
|
||||
[0] 0.0
|
||||
[1] 0.5
|
||||
}
|
||||
}
|
||||
|
||||
trot
|
||||
{
|
||||
modeSequence
|
||||
{
|
||||
[0] LF_RH
|
||||
[1] RF_LH
|
||||
}
|
||||
switchingTimes
|
||||
{
|
||||
[0] 0.0
|
||||
[1] 0.3
|
||||
[2] 0.6
|
||||
}
|
||||
}
|
||||
|
||||
standing_trot
|
||||
{
|
||||
modeSequence
|
||||
{
|
||||
[0] LF_RH
|
||||
[1] STANCE
|
||||
[2] RF_LH
|
||||
[3] STANCE
|
||||
}
|
||||
switchingTimes
|
||||
{
|
||||
[0] 0.00
|
||||
[1] 0.25
|
||||
[2] 0.3
|
||||
[3] 0.55
|
||||
[4] 0.6
|
||||
}
|
||||
}
|
||||
|
||||
flying_trot
|
||||
{
|
||||
modeSequence
|
||||
{
|
||||
[0] LF_RH
|
||||
[1] FLY
|
||||
[2] RF_LH
|
||||
[3] FLY
|
||||
}
|
||||
switchingTimes
|
||||
{
|
||||
[0] 0.00
|
||||
[1] 0.15
|
||||
[2] 0.2
|
||||
[3] 0.35
|
||||
[4] 0.4
|
||||
}
|
||||
}
|
||||
|
||||
pace
|
||||
{
|
||||
modeSequence
|
||||
{
|
||||
[0] LF_LH
|
||||
[1] FLY
|
||||
[2] RF_RH
|
||||
[3] FLY
|
||||
}
|
||||
switchingTimes
|
||||
{
|
||||
[0] 0.0
|
||||
[1] 0.28
|
||||
[2] 0.30
|
||||
[3] 0.58
|
||||
[4] 0.60
|
||||
}
|
||||
}
|
||||
|
||||
standing_pace
|
||||
{
|
||||
modeSequence
|
||||
{
|
||||
[0] LF_LH
|
||||
[1] STANCE
|
||||
[2] RF_RH
|
||||
[3] STANCE
|
||||
}
|
||||
switchingTimes
|
||||
{
|
||||
[0] 0.0
|
||||
[1] 0.30
|
||||
[2] 0.35
|
||||
[3] 0.65
|
||||
[4] 0.70
|
||||
}
|
||||
}
|
||||
|
||||
dynamic_walk
|
||||
{
|
||||
modeSequence
|
||||
{
|
||||
[0] LF_RF_RH
|
||||
[1] RF_RH
|
||||
[2] RF_LH_RH
|
||||
[3] LF_RF_LH
|
||||
[4] LF_LH
|
||||
[5] LF_LH_RH
|
||||
}
|
||||
switchingTimes
|
||||
{
|
||||
[0] 0.0
|
||||
[1] 0.2
|
||||
[2] 0.3
|
||||
[3] 0.5
|
||||
[4] 0.7
|
||||
[5] 0.8
|
||||
[6] 1.0
|
||||
}
|
||||
}
|
||||
|
||||
static_walk
|
||||
{
|
||||
modeSequence
|
||||
{
|
||||
[0] LF_RF_RH
|
||||
[1] RF_LH_RH
|
||||
[2] LF_RF_LH
|
||||
[3] LF_LH_RH
|
||||
}
|
||||
switchingTimes
|
||||
{
|
||||
[0] 0.0
|
||||
[1] 0.3
|
||||
[2] 0.6
|
||||
[3] 0.9
|
||||
[4] 1.2
|
||||
}
|
||||
}
|
||||
|
||||
amble
|
||||
{
|
||||
modeSequence
|
||||
{
|
||||
[0] RF_LH
|
||||
[1] LF_LH
|
||||
[2] LF_RH
|
||||
[3] RF_RH
|
||||
}
|
||||
switchingTimes
|
||||
{
|
||||
[0] 0.0
|
||||
[1] 0.15
|
||||
[2] 0.40
|
||||
[3] 0.55
|
||||
[4] 0.80
|
||||
}
|
||||
}
|
||||
|
||||
lindyhop
|
||||
{
|
||||
modeSequence
|
||||
{
|
||||
[0] LF_RH
|
||||
[1] STANCE
|
||||
[2] RF_LH
|
||||
[3] STANCE
|
||||
[4] LF_LH
|
||||
[5] RF_RH
|
||||
[6] LF_LH
|
||||
[7] STANCE
|
||||
[8] RF_RH
|
||||
[9] LF_LH
|
||||
[10] RF_RH
|
||||
[11] STANCE
|
||||
}
|
||||
switchingTimes
|
||||
{
|
||||
[0] 0.00 ; Step 1
|
||||
[1] 0.35 ; Stance
|
||||
[2] 0.45 ; Step 2
|
||||
[3] 0.80 ; Stance
|
||||
[4] 0.90 ; Tripple step
|
||||
[5] 1.125 ;
|
||||
[6] 1.35 ;
|
||||
[7] 1.70 ; Stance
|
||||
[8] 1.80 ; Tripple step
|
||||
[9] 2.025 ;
|
||||
[10] 2.25 ;
|
||||
[11] 2.60 ; Stance
|
||||
[12] 2.70 ;
|
||||
}
|
||||
}
|
||||
|
||||
skipping
|
||||
{
|
||||
modeSequence
|
||||
{
|
||||
[0] LF_RH
|
||||
[1] FLY
|
||||
[2] LF_RH
|
||||
[3] FLY
|
||||
[4] RF_LH
|
||||
[5] FLY
|
||||
[6] RF_LH
|
||||
[7] FLY
|
||||
}
|
||||
switchingTimes
|
||||
{
|
||||
[0] 0.00
|
||||
[1] 0.27
|
||||
[2] 0.30
|
||||
[3] 0.57
|
||||
[4] 0.60
|
||||
[5] 0.87
|
||||
[6] 0.90
|
||||
[7] 1.17
|
||||
[8] 1.20
|
||||
}
|
||||
}
|
||||
|
||||
pawup
|
||||
{
|
||||
modeSequence
|
||||
{
|
||||
[0] RF_LH_RH
|
||||
}
|
||||
switchingTimes
|
||||
{
|
||||
[0] 0.0
|
||||
[1] 2.0
|
||||
}
|
||||
}
|
|
@ -0,0 +1,46 @@
|
|||
targetDisplacementVelocity 0.5;
|
||||
targetRotationVelocity 1.57;
|
||||
|
||||
comHeight 0.33
|
||||
|
||||
defaultJointState
|
||||
{
|
||||
(0,0) -0.20 ; FL_hip_joint
|
||||
(1,0) 0.72 ; FL_thigh_joint
|
||||
(2,0) -1.44 ; FL_calf_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.20 ; RL_hip_joint
|
||||
(7,0) 0.72 ; RL_thigh_joint
|
||||
(8,0) -1.44 ; RL_calf_joint
|
||||
(9,0) 0.20 ; RR_hip_joint
|
||||
(10,0) 0.72 ; 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
|
||||
}
|
||||
}
|
|
@ -0,0 +1,319 @@
|
|||
centroidalModelType 0 // 0: FullCentroidalDynamics, 1: Single Rigid Body Dynamics
|
||||
|
||||
legged_robot_interface
|
||||
{
|
||||
verbose false // show the loaded parameters
|
||||
}
|
||||
|
||||
model_settings
|
||||
{
|
||||
positionErrorGain 0.0
|
||||
phaseTransitionStanceTime 0.1
|
||||
|
||||
verboseCppAd true
|
||||
recompileLibrariesCppAd false
|
||||
modelFolderCppAd /tmp/ocs2_quadruped_controller/a1
|
||||
}
|
||||
|
||||
swing_trajectory_config
|
||||
{
|
||||
liftOffVelocity 0.05
|
||||
touchDownVelocity -0.1
|
||||
swingHeight 0.1
|
||||
swingTimeScale 0.15
|
||||
}
|
||||
|
||||
; DDP settings
|
||||
ddp
|
||||
{
|
||||
algorithm SLQ
|
||||
|
||||
nThreads 3
|
||||
threadPriority 50
|
||||
|
||||
maxNumIterations 1
|
||||
minRelCost 1e-1
|
||||
constraintTolerance 5e-3
|
||||
|
||||
displayInfo false
|
||||
displayShortSummary false
|
||||
checkNumericalStability false
|
||||
debugPrintRollout false
|
||||
debugCaching false
|
||||
|
||||
AbsTolODE 1e-5
|
||||
RelTolODE 1e-3
|
||||
maxNumStepsPerSecond 10000
|
||||
timeStep 0.015
|
||||
backwardPassIntegratorType ODE45
|
||||
|
||||
constraintPenaltyInitialValue 20.0
|
||||
constraintPenaltyIncreaseRate 2.0
|
||||
|
||||
preComputeRiccatiTerms true
|
||||
|
||||
useFeedbackPolicy false
|
||||
|
||||
strategy LINE_SEARCH
|
||||
lineSearch
|
||||
{
|
||||
minStepLength 1e-2
|
||||
maxStepLength 1.0
|
||||
hessianCorrectionStrategy DIAGONAL_SHIFT
|
||||
hessianCorrectionMultiple 1e-5
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
; Multiple_Shooting SQP settings
|
||||
sqp
|
||||
{
|
||||
nThreads 3
|
||||
dt 0.015
|
||||
sqpIteration 1
|
||||
deltaTol 1e-4
|
||||
g_max 1e-2
|
||||
g_min 1e-6
|
||||
inequalityConstraintMu 0.1
|
||||
inequalityConstraintDelta 5.0
|
||||
projectStateInputEqualityConstraints true
|
||||
printSolverStatistics true
|
||||
printSolverStatus false
|
||||
printLinesearch false
|
||||
useFeedbackPolicy false
|
||||
integratorType RK2
|
||||
threadPriority 50
|
||||
}
|
||||
|
||||
; Multiple_Shooting IPM settings
|
||||
ipm
|
||||
{
|
||||
nThreads 3
|
||||
dt 0.015
|
||||
ipmIteration 1
|
||||
deltaTol 1e-4
|
||||
g_max 10.0
|
||||
g_min 1e-6
|
||||
computeLagrangeMultipliers true
|
||||
printSolverStatistics true
|
||||
printSolverStatus false
|
||||
printLinesearch false
|
||||
useFeedbackPolicy false
|
||||
integratorType RK2
|
||||
threadPriority 50
|
||||
|
||||
initialBarrierParameter 1e-4
|
||||
targetBarrierParameter 1e-4
|
||||
barrierLinearDecreaseFactor 0.2
|
||||
barrierSuperlinearDecreasePower 1.5
|
||||
barrierReductionCostTol 1e-3
|
||||
barrierReductionConstraintTol 1e-3
|
||||
|
||||
fractionToBoundaryMargin 0.995
|
||||
usePrimalStepSizeForDual false
|
||||
|
||||
initialSlackLowerBound 1e-4
|
||||
initialDualLowerBound 1e-4
|
||||
initialSlackMarginRate 1e-2
|
||||
initialDualMarginRate 1e-2
|
||||
}
|
||||
|
||||
; Rollout settings
|
||||
rollout
|
||||
{
|
||||
AbsTolODE 1e-5
|
||||
RelTolODE 1e-3
|
||||
timeStep 0.015
|
||||
integratorType ODE45
|
||||
maxNumStepsPerSecond 10000
|
||||
checkNumericalStability false
|
||||
}
|
||||
|
||||
mpc
|
||||
{
|
||||
timeHorizon 1.0 ; [s]
|
||||
solutionTimeWindow -1 ; maximum [s]
|
||||
coldStart false
|
||||
|
||||
debugPrint false
|
||||
|
||||
mpcDesiredFrequency 100 ; [Hz]
|
||||
mrtDesiredFrequency 1000 ; [Hz] Useless
|
||||
}
|
||||
|
||||
initialState
|
||||
{
|
||||
;; Normalized Centroidal Momentum: [linear, angular] ;;
|
||||
(0,0) 0.0 ; vcom_x
|
||||
(1,0) 0.0 ; vcom_y
|
||||
(2,0) 0.0 ; vcom_z
|
||||
(3,0) 0.0 ; L_x / robotMass
|
||||
(4,0) 0.0 ; L_y / robotMass
|
||||
(5,0) 0.0 ; L_z / robotMass
|
||||
|
||||
;; Base Pose: [position, orientation] ;;
|
||||
(6,0) 0.0 ; p_base_x
|
||||
(7,0) 0.0 ; p_base_y
|
||||
(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
|
||||
|
||||
;; Leg Joint Positions: [FL, RL, FR, RR] ;;
|
||||
(12,0) -0.20 ; FL_hip_joint
|
||||
(13,0) 0.72 ; FL_thigh_joint
|
||||
(14,0) -1.44 ; FL_calf_joint
|
||||
(15,0) -0.20 ; RL_hip_joint
|
||||
(16,0) 0.72 ; RL_thigh_joint
|
||||
(17,0) -1.44 ; RL_calf_joint
|
||||
(18,0) 0.20 ; FR_hip_joint
|
||||
(19,0) 0.72 ; FR_thigh_joint
|
||||
(20,0) -1.44 ; FR_calf_joint
|
||||
(21,0) 0.20 ; RR_hip_joint
|
||||
(22,0) 0.72 ; RR_thigh_joint
|
||||
(23,0) -1.44 ; RR_calf_joint
|
||||
}
|
||||
|
||||
; standard state weight matrix
|
||||
Q
|
||||
{
|
||||
scaling 1e+0
|
||||
|
||||
;; Normalized Centroidal Momentum: [linear, angular] ;;
|
||||
(0,0) 15.0 ; vcom_x
|
||||
(1,1) 15.0 ; vcom_y
|
||||
(2,2) 100.0 ; vcom_z
|
||||
(3,3) 10.0 ; L_x / robotMass
|
||||
(4,4) 30.0 ; L_y / robotMass
|
||||
(5,5) 30.0 ; L_z / robotMass
|
||||
|
||||
;; Base Pose: [position, orientation] ;;
|
||||
(6,6) 1000.0 ; p_base_x
|
||||
(7,7) 1000.0 ; p_base_y
|
||||
(8,8) 1500.0 ; p_base_z
|
||||
(9,9) 100.0 ; theta_base_z
|
||||
(10,10) 300.0 ; theta_base_y
|
||||
(11,11) 300.0 ; theta_base_x
|
||||
|
||||
;; Leg Joint Positions: [FL, RL, FR, RR] ;;
|
||||
(12,12) 5.0 ; FL_hip_joint
|
||||
(13,13) 5.0 ; FL_thigh_joint
|
||||
(14,14) 2.5 ; FL_calf_joint
|
||||
(15,15) 5.0 ; RL_hip_joint
|
||||
(16,16) 5.0 ; RL_thigh_joint
|
||||
(17,17) 2.5 ; RL_calf_joint
|
||||
(18,18) 5.0 ; FR_hip_joint
|
||||
(19,19) 5.0 ; FR_thigh_joint
|
||||
(20,20) 2.5 ; FR_calf_joint
|
||||
(21,21) 5.0 ; RR_hip_joint
|
||||
(22,22) 5.0 ; RR_thigh_joint
|
||||
(23,23) 2.5 ; RR_calf_joint
|
||||
}
|
||||
|
||||
; control weight matrix
|
||||
R
|
||||
{
|
||||
scaling 1e-3
|
||||
|
||||
;; Feet Contact Forces: [FL, FR, RL, RR] ;;
|
||||
(0,0) 1.0 ; front_left_force
|
||||
(1,1) 1.0 ; front_left_force
|
||||
(2,2) 1.0 ; front_left_force
|
||||
(3,3) 1.0 ; front_right_force
|
||||
(4,4) 1.0 ; front_right_force
|
||||
(5,5) 1.0 ; front_right_force
|
||||
(6,6) 1.0 ; rear_left_force
|
||||
(7,7) 1.0 ; rear_left_force
|
||||
(8,8) 1.0 ; rear_left_force
|
||||
(9,9) 1.0 ; rear_right_force
|
||||
(10,10) 1.0 ; rear_right_force
|
||||
(11,11) 1.0 ; rear_right_force
|
||||
|
||||
;; foot velocity relative to base: [FL, RL, FR, RR] (uses the Jacobian at nominal configuration) ;;
|
||||
(12,12) 5000.0 ; x
|
||||
(13,13) 5000.0 ; y
|
||||
(14,14) 5000.0 ; z
|
||||
(15,15) 5000.0 ; x
|
||||
(16,16) 5000.0 ; y
|
||||
(17,17) 5000.0 ; z
|
||||
(18,18) 5000.0 ; x
|
||||
(19,19) 5000.0 ; y
|
||||
(20,20) 5000.0 ; z
|
||||
(21,21) 5000.0 ; x
|
||||
(22,22) 5000.0 ; y
|
||||
(23,23) 5000.0 ; z
|
||||
}
|
||||
|
||||
frictionConeSoftConstraint
|
||||
{
|
||||
frictionCoefficient 0.3
|
||||
|
||||
; relaxed log barrier parameters
|
||||
mu 0.1
|
||||
delta 5.0
|
||||
}
|
||||
|
||||
selfCollision
|
||||
{
|
||||
; Self Collision raw object pairs
|
||||
collisionObjectPairs
|
||||
{
|
||||
}
|
||||
|
||||
; Self Collision pairs
|
||||
collisionLinkPairs
|
||||
{
|
||||
[0] "FL_calf, FR_calf"
|
||||
[1] "RL_calf, RR_calf"
|
||||
[2] "FL_calf, RL_calf"
|
||||
[3] "FR_calf, RR_calf"
|
||||
[4] "FL_foot, FR_foot"
|
||||
[5] "RL_foot, RR_foot"
|
||||
[6] "FL_foot, RL_foot"
|
||||
[7] "FR_foot, RR_foot"
|
||||
}
|
||||
|
||||
minimumDistance 0.05
|
||||
|
||||
; relaxed log barrier parameters
|
||||
mu 1e-2
|
||||
delta 1e-3
|
||||
}
|
||||
|
||||
; Whole body control
|
||||
torqueLimitsTask
|
||||
{
|
||||
(0,0) 33.5 ; HAA
|
||||
(1,0) 33.5 ; HFE
|
||||
(2,0) 33.5 ; KFE
|
||||
}
|
||||
|
||||
frictionConeTask
|
||||
{
|
||||
frictionCoefficient 0.3
|
||||
}
|
||||
|
||||
swingLegTask
|
||||
{
|
||||
kp 350
|
||||
kd 37
|
||||
}
|
||||
|
||||
weight
|
||||
{
|
||||
swingLeg 100
|
||||
baseAccel 1
|
||||
contactForce 0.01
|
||||
}
|
||||
|
||||
; State Estimation
|
||||
kalmanFilter
|
||||
{
|
||||
footRadius 0.02
|
||||
imuProcessNoisePosition 0.02
|
||||
imuProcessNoiseVelocity 0.02
|
||||
footProcessNoisePosition 0.002
|
||||
footSensorNoisePosition 0.005
|
||||
footSensorNoiseVelocity 0.1
|
||||
footHeightSensorNoise 0.01
|
||||
}
|
|
@ -0,0 +1,131 @@
|
|||
# Controller Manager configuration
|
||||
controller_manager:
|
||||
ros__parameters:
|
||||
update_rate: 500 # Hz
|
||||
|
||||
# Define the available controllers
|
||||
joint_state_broadcaster:
|
||||
type: joint_state_broadcaster/JointStateBroadcaster
|
||||
|
||||
imu_sensor_broadcaster:
|
||||
type: imu_sensor_broadcaster/IMUSensorBroadcaster
|
||||
|
||||
unitree_guide_controller:
|
||||
type: unitree_guide_controller/UnitreeGuideController
|
||||
|
||||
ocs2_quadruped_controller:
|
||||
type: ocs2_quadruped_controller/Ocs2QuadrupedController
|
||||
|
||||
imu_sensor_broadcaster:
|
||||
ros__parameters:
|
||||
sensor_name: "imu_sensor"
|
||||
frame_id: "imu_link"
|
||||
|
||||
unitree_guide_controller:
|
||||
ros__parameters:
|
||||
update_rate: 500 # Hz
|
||||
joints:
|
||||
- FR_hip_joint
|
||||
- FR_thigh_joint
|
||||
- FR_calf_joint
|
||||
- FL_hip_joint
|
||||
- FL_thigh_joint
|
||||
- FL_calf_joint
|
||||
- RR_hip_joint
|
||||
- RR_thigh_joint
|
||||
- RR_calf_joint
|
||||
- RL_hip_joint
|
||||
- RL_thigh_joint
|
||||
- RL_calf_joint
|
||||
|
||||
command_interfaces:
|
||||
- effort
|
||||
- position
|
||||
- velocity
|
||||
- kp
|
||||
- kd
|
||||
|
||||
state_interfaces:
|
||||
- effort
|
||||
- position
|
||||
- velocity
|
||||
|
||||
feet_names:
|
||||
- FR_foot
|
||||
- FL_foot
|
||||
- RR_foot
|
||||
- RL_foot
|
||||
|
||||
imu_name: "imu_sensor"
|
||||
base_name: "base"
|
||||
|
||||
imu_interfaces:
|
||||
- orientation.w
|
||||
- orientation.x
|
||||
- orientation.y
|
||||
- orientation.z
|
||||
- angular_velocity.x
|
||||
- angular_velocity.y
|
||||
- angular_velocity.z
|
||||
- linear_acceleration.x
|
||||
- linear_acceleration.y
|
||||
- linear_acceleration.z
|
||||
|
||||
ocs2_quadruped_controller:
|
||||
ros__parameters:
|
||||
update_rate: 500 # Hz
|
||||
|
||||
joints:
|
||||
- FL_hip_joint
|
||||
- FL_thigh_joint
|
||||
- FL_calf_joint
|
||||
- FR_hip_joint
|
||||
- FR_thigh_joint
|
||||
- FR_calf_joint
|
||||
- RL_hip_joint
|
||||
- RL_thigh_joint
|
||||
- RL_calf_joint
|
||||
- RR_hip_joint
|
||||
- RR_thigh_joint
|
||||
- RR_calf_joint
|
||||
|
||||
command_interfaces:
|
||||
- effort
|
||||
- position
|
||||
- velocity
|
||||
- kp
|
||||
- kd
|
||||
|
||||
state_interfaces:
|
||||
- effort
|
||||
- position
|
||||
- velocity
|
||||
|
||||
feet_names:
|
||||
- FL_foot
|
||||
- FR_foot
|
||||
- RL_foot
|
||||
- RR_foot
|
||||
|
||||
|
||||
imu_name: "imu_sensor"
|
||||
base_name: "base"
|
||||
|
||||
imu_interfaces:
|
||||
- orientation.w
|
||||
- orientation.x
|
||||
- orientation.y
|
||||
- orientation.z
|
||||
- angular_velocity.x
|
||||
- angular_velocity.y
|
||||
- angular_velocity.z
|
||||
- linear_acceleration.x
|
||||
- linear_acceleration.y
|
||||
- linear_acceleration.z
|
||||
|
||||
foot_force_name: "foot_force"
|
||||
foot_force_interfaces:
|
||||
- FL
|
||||
- RL
|
||||
- FR
|
||||
- RR
|
|
@ -0,0 +1,383 @@
|
|||
Panels:
|
||||
- Class: rviz_common/Displays
|
||||
Help Height: 138
|
||||
Name: Displays
|
||||
Property Tree Widget:
|
||||
Expanded:
|
||||
- /Global Options1
|
||||
- /Status1
|
||||
- /RobotModel1
|
||||
Splitter Ratio: 0.5
|
||||
Tree Height: 303
|
||||
- Class: rviz_common/Selection
|
||||
Name: Selection
|
||||
- Class: rviz_common/Tool Properties
|
||||
Expanded:
|
||||
- /2D Goal Pose1
|
||||
- /Publish Point1
|
||||
Name: Tool Properties
|
||||
Splitter Ratio: 0.5886790156364441
|
||||
- Class: rviz_common/Views
|
||||
Expanded:
|
||||
- /Current View1
|
||||
Name: Views
|
||||
Splitter Ratio: 0.5
|
||||
- Class: rviz_common/Time
|
||||
Experimental: false
|
||||
Name: Time
|
||||
SyncMode: 0
|
||||
SyncSource: ""
|
||||
Visualization Manager:
|
||||
Class: ""
|
||||
Displays:
|
||||
- Alpha: 0.5
|
||||
Cell Size: 1
|
||||
Class: rviz_default_plugins/Grid
|
||||
Color: 160; 160; 164
|
||||
Enabled: true
|
||||
Line Style:
|
||||
Line Width: 0.029999999329447746
|
||||
Value: Lines
|
||||
Name: Grid
|
||||
Normal Cell Count: 0
|
||||
Offset:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Plane: XY
|
||||
Plane Cell Count: 10
|
||||
Reference Frame: <Fixed Frame>
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Class: rviz_default_plugins/RobotModel
|
||||
Collision Enabled: false
|
||||
Description File: ""
|
||||
Description Source: Topic
|
||||
Description Topic:
|
||||
Depth: 5
|
||||
Durability Policy: Volatile
|
||||
History Policy: Keep Last
|
||||
Reliability Policy: Reliable
|
||||
Value: /robot_description
|
||||
Enabled: true
|
||||
Links:
|
||||
All Links Enabled: true
|
||||
Expand Joint Details: false
|
||||
Expand Link Details: false
|
||||
Expand Tree: false
|
||||
FL_calf:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_calf_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_foot:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_hip:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_hip_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_thigh:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_thigh_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_calf:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_calf_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_foot:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_hip:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_hip_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_thigh:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_thigh_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
Link Tree Style: Links in Alphabetic Order
|
||||
RL_calf:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_calf_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_foot:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_hip:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_hip_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_thigh:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RL_thigh_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_calf:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_calf_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_foot:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_hip:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_hip_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_thigh:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
RR_thigh_rotor:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
base:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
camera_chin:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
camera_face:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
camera_laserscan_link_left:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
camera_laserscan_link_right:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
camera_left:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
camera_optical_chin:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
camera_optical_face:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
camera_optical_left:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
camera_optical_rearDown:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
camera_optical_right:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
camera_rearDown:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
camera_right:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
imu_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
trunk:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
ultraSound_face:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
ultraSound_left:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
ultraSound_right:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
Mass Properties:
|
||||
Inertia: false
|
||||
Mass: false
|
||||
Name: RobotModel
|
||||
TF Prefix: ""
|
||||
Update Interval: 0
|
||||
Value: true
|
||||
Visual Enabled: true
|
||||
Enabled: true
|
||||
Global Options:
|
||||
Background Color: 48; 48; 48
|
||||
Fixed Frame: base
|
||||
Frame Rate: 30
|
||||
Name: root
|
||||
Tools:
|
||||
- Class: rviz_default_plugins/Interact
|
||||
Hide Inactive Objects: true
|
||||
- Class: rviz_default_plugins/MoveCamera
|
||||
- Class: rviz_default_plugins/Select
|
||||
- Class: rviz_default_plugins/FocusCamera
|
||||
- Class: rviz_default_plugins/Measure
|
||||
Line color: 128; 128; 0
|
||||
- Class: rviz_default_plugins/SetInitialPose
|
||||
Covariance x: 0.25
|
||||
Covariance y: 0.25
|
||||
Covariance yaw: 0.06853891909122467
|
||||
Topic:
|
||||
Depth: 5
|
||||
Durability Policy: Volatile
|
||||
History Policy: Keep Last
|
||||
Reliability Policy: Reliable
|
||||
Value: /initialpose
|
||||
- Class: rviz_default_plugins/SetGoal
|
||||
Topic:
|
||||
Depth: 5
|
||||
Durability Policy: Volatile
|
||||
History Policy: Keep Last
|
||||
Reliability Policy: Reliable
|
||||
Value: /goal_pose
|
||||
- Class: rviz_default_plugins/PublishPoint
|
||||
Single click: true
|
||||
Topic:
|
||||
Depth: 5
|
||||
Durability Policy: Volatile
|
||||
History Policy: Keep Last
|
||||
Reliability Policy: Reliable
|
||||
Value: /clicked_point
|
||||
Transformation:
|
||||
Current:
|
||||
Class: rviz_default_plugins/TF
|
||||
Value: true
|
||||
Views:
|
||||
Current:
|
||||
Class: rviz_default_plugins/Orbit
|
||||
Distance: 0.8687032461166382
|
||||
Enable Stereo Rendering:
|
||||
Stereo Eye Separation: 0.05999999865889549
|
||||
Stereo Focal Distance: 1
|
||||
Swap Stereo Eyes: false
|
||||
Value: false
|
||||
Focal Point:
|
||||
X: 0.017344314604997635
|
||||
Y: -0.0033522010780870914
|
||||
Z: -0.09058035165071487
|
||||
Focal Shape Fixed Size: true
|
||||
Focal Shape Size: 0.05000000074505806
|
||||
Invert Z Axis: false
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.009999999776482582
|
||||
Pitch: 0.49539798498153687
|
||||
Target Frame: <Fixed Frame>
|
||||
Value: Orbit (rviz)
|
||||
Yaw: 0.8403961062431335
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
collapsed: true
|
||||
Height: 630
|
||||
Hide Left Dock: true
|
||||
Hide Right Dock: true
|
||||
QMainWindow State: 000000ff00000000fd0000000400000000000001f40000043cfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007300000000700000043c000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000015d0000043cfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000700000043c000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003130000005efc0100000002fb0000000800540069006d0065010000000000000313000002fb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000313000001b800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
Selection:
|
||||
collapsed: false
|
||||
Time:
|
||||
collapsed: false
|
||||
Tool Properties:
|
||||
collapsed: false
|
||||
Views:
|
||||
collapsed: true
|
||||
Width: 787
|
||||
X: 763
|
||||
Y: 351
|
|
@ -0,0 +1,122 @@
|
|||
import os
|
||||
|
||||
import xacro
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument, OpaqueFunction, IncludeLaunchDescription, RegisterEventHandler
|
||||
from launch.event_handlers import OnProcessExit
|
||||
from launch.substitutions import PathJoinSubstitution
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
from sympy.physics.vector.printing import params
|
||||
|
||||
package_description = "a1_description"
|
||||
package_controller = "ocs2_quadruped_controller"
|
||||
|
||||
def process_xacro(context):
|
||||
robot_type_value = context.launch_configurations['robot_type']
|
||||
pkg_path = os.path.join(get_package_share_directory(package_description))
|
||||
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
|
||||
robot_description_config = xacro.process_file(xacro_file, mappings={'robot_type': robot_type_value})
|
||||
return (robot_description_config.toxml(), robot_type_value)
|
||||
|
||||
|
||||
def launch_setup(context, *args, **kwargs):
|
||||
(robot_description, robot_type) = process_xacro(context)
|
||||
robot_controllers = PathJoinSubstitution(
|
||||
[
|
||||
FindPackageShare(package_description),
|
||||
"config",
|
||||
"robot_control.yaml",
|
||||
]
|
||||
)
|
||||
|
||||
robot_state_publisher = Node(
|
||||
package='robot_state_publisher',
|
||||
executable='robot_state_publisher',
|
||||
name='robot_state_publisher',
|
||||
parameters=[
|
||||
{
|
||||
'publish_frequency': 20.0,
|
||||
'use_tf_static': True,
|
||||
'robot_description': robot_description,
|
||||
'ignore_timestamp': True
|
||||
}
|
||||
],
|
||||
)
|
||||
|
||||
controller_manager = Node(
|
||||
package="controller_manager",
|
||||
executable="ros2_control_node",
|
||||
parameters=[robot_controllers,
|
||||
{
|
||||
'urdf_file': os.path.join(get_package_share_directory(package_description), 'urdf', 'robot.urdf'),
|
||||
'task_file': os.path.join(get_package_share_directory(package_description), 'config', 'ocs2',
|
||||
'task.info'),
|
||||
'reference_file': os.path.join(get_package_share_directory(package_description), 'config',
|
||||
'ocs2', 'reference.info'),
|
||||
'gait_file': os.path.join(get_package_share_directory(package_description), 'config',
|
||||
'ocs2', 'gait.info')
|
||||
}],
|
||||
output="both",
|
||||
)
|
||||
|
||||
joint_state_publisher = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=["joint_state_broadcaster",
|
||||
"--controller-manager", "/controller_manager"],
|
||||
)
|
||||
|
||||
imu_sensor_broadcaster = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=["imu_sensor_broadcaster",
|
||||
"--controller-manager", "/controller_manager"],
|
||||
)
|
||||
|
||||
ocs2_controller = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=["ocs2_quadruped_controller", "--controller-manager", "/controller_manager"]
|
||||
)
|
||||
|
||||
return [
|
||||
robot_state_publisher,
|
||||
controller_manager,
|
||||
joint_state_publisher,
|
||||
RegisterEventHandler(
|
||||
event_handler=OnProcessExit(
|
||||
target_action=joint_state_publisher,
|
||||
on_exit=[imu_sensor_broadcaster],
|
||||
)
|
||||
),
|
||||
RegisterEventHandler(
|
||||
event_handler=OnProcessExit(
|
||||
target_action=imu_sensor_broadcaster,
|
||||
on_exit=[ocs2_controller],
|
||||
)
|
||||
),
|
||||
]
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
robot_type_arg = DeclareLaunchArgument(
|
||||
'robot_type',
|
||||
default_value='a1',
|
||||
description='Type of the robot'
|
||||
)
|
||||
|
||||
rviz_config_file = os.path.join(get_package_share_directory(package_controller), "config", "visualize_ocs2.rviz")
|
||||
|
||||
return LaunchDescription([
|
||||
robot_type_arg,
|
||||
OpaqueFunction(function=launch_setup),
|
||||
Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
name='rviz_ocs2',
|
||||
output='screen',
|
||||
arguments=["-d", rviz_config_file]
|
||||
)
|
||||
])
|
|
@ -0,0 +1,112 @@
|
|||
import os
|
||||
|
||||
import xacro
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument, OpaqueFunction, IncludeLaunchDescription, RegisterEventHandler
|
||||
from launch.event_handlers import OnProcessExit
|
||||
from launch.substitutions import PathJoinSubstitution
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
|
||||
package_description = "a1_description"
|
||||
|
||||
|
||||
def process_xacro(context):
|
||||
robot_type_value = context.launch_configurations['robot_type']
|
||||
pkg_path = os.path.join(get_package_share_directory(package_description))
|
||||
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
|
||||
robot_description_config = xacro.process_file(xacro_file, mappings={'robot_type': robot_type_value})
|
||||
return (robot_description_config.toxml(), robot_type_value)
|
||||
|
||||
|
||||
def launch_setup(context, *args, **kwargs):
|
||||
(robot_description, robot_type) = process_xacro(context)
|
||||
robot_controllers = PathJoinSubstitution(
|
||||
[
|
||||
FindPackageShare(package_description),
|
||||
"config",
|
||||
"robot_control.yaml",
|
||||
]
|
||||
)
|
||||
|
||||
robot_state_publisher = Node(
|
||||
package='robot_state_publisher',
|
||||
executable='robot_state_publisher',
|
||||
name='robot_state_publisher',
|
||||
parameters=[
|
||||
{
|
||||
'publish_frequency': 20.0,
|
||||
'use_tf_static': True,
|
||||
'robot_description': robot_description,
|
||||
'ignore_timestamp': True
|
||||
}
|
||||
],
|
||||
)
|
||||
|
||||
controller_manager = Node(
|
||||
package="controller_manager",
|
||||
executable="ros2_control_node",
|
||||
parameters=[robot_controllers],
|
||||
output="both",
|
||||
)
|
||||
|
||||
joint_state_publisher = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=["joint_state_broadcaster",
|
||||
"--controller-manager", "/controller_manager"],
|
||||
)
|
||||
|
||||
imu_sensor_broadcaster = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=["imu_sensor_broadcaster",
|
||||
"--controller-manager", "/controller_manager"],
|
||||
)
|
||||
|
||||
unitree_guide_controller = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=["unitree_guide_controller", "--controller-manager", "/controller_manager"],
|
||||
)
|
||||
|
||||
return [
|
||||
robot_state_publisher,
|
||||
controller_manager,
|
||||
joint_state_publisher,
|
||||
RegisterEventHandler(
|
||||
event_handler=OnProcessExit(
|
||||
target_action=joint_state_publisher,
|
||||
on_exit=[imu_sensor_broadcaster],
|
||||
)
|
||||
),
|
||||
RegisterEventHandler(
|
||||
event_handler=OnProcessExit(
|
||||
target_action=imu_sensor_broadcaster,
|
||||
on_exit=[unitree_guide_controller],
|
||||
)
|
||||
),
|
||||
]
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
robot_type_arg = DeclareLaunchArgument(
|
||||
'robot_type',
|
||||
default_value='a1',
|
||||
description='Type of the robot'
|
||||
)
|
||||
|
||||
rviz_config_file = os.path.join(get_package_share_directory(package_description), "config", "visualize_urdf.rviz")
|
||||
|
||||
return LaunchDescription([
|
||||
robot_type_arg,
|
||||
OpaqueFunction(function=launch_setup),
|
||||
Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
name='rviz_ocs2',
|
||||
output='screen',
|
||||
arguments=["-d", rviz_config_file]
|
||||
)
|
||||
])
|
|
@ -0,0 +1,66 @@
|
|||
import os
|
||||
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument, OpaqueFunction
|
||||
from launch_ros.actions import Node
|
||||
|
||||
import xacro
|
||||
|
||||
package_description = "a1_description"
|
||||
|
||||
|
||||
def process_xacro(context):
|
||||
robot_type_value = context.launch_configurations['robot_type']
|
||||
pkg_path = os.path.join(get_package_share_directory(package_description))
|
||||
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
|
||||
robot_description_config = xacro.process_file(xacro_file, mappings={'robot_type': robot_type_value})
|
||||
return robot_description_config.toxml()
|
||||
|
||||
|
||||
def launch_setup(context, *args, **kwargs):
|
||||
robot_description = process_xacro(context)
|
||||
return [
|
||||
Node(
|
||||
package='robot_state_publisher',
|
||||
executable='robot_state_publisher',
|
||||
name='robot_state_publisher',
|
||||
output='screen',
|
||||
parameters=[
|
||||
{
|
||||
'publish_frequency': 100.0,
|
||||
'use_tf_static': True,
|
||||
'robot_description': robot_description
|
||||
}
|
||||
],
|
||||
),
|
||||
Node(
|
||||
package='joint_state_publisher_gui',
|
||||
executable='joint_state_publisher_gui',
|
||||
name='joint_state_publisher',
|
||||
output='screen',
|
||||
)
|
||||
]
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
robot_type_arg = DeclareLaunchArgument(
|
||||
'robot_type',
|
||||
default_value='a1',
|
||||
description='Type of the robot'
|
||||
)
|
||||
|
||||
rviz_config_file = os.path.join(get_package_share_directory(package_description), "config", "visualize_urdf.rviz")
|
||||
|
||||
return LaunchDescription([
|
||||
robot_type_arg,
|
||||
OpaqueFunction(function=launch_setup),
|
||||
Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
name='rviz_ocs2',
|
||||
output='screen',
|
||||
arguments=["-d", rviz_config_file]
|
||||
)
|
||||
])
|
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
Binary file not shown.
After Width: | Height: | Size: 70 KiB |
|
@ -0,0 +1,19 @@
|
|||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>a1_description</name>
|
||||
<version>0.0.0</version>
|
||||
<description>The a1_description package</description>
|
||||
|
||||
<maintainer email="laikago@unitree.cc">unitree</maintainer>
|
||||
<license>TODO</license>
|
||||
|
||||
<exec_depend>xacro</exec_depend>
|
||||
<exec_depend>joint_state_publisher</exec_depend>
|
||||
<exec_depend>robot_state_publisher</exec_depend>
|
||||
<exec_depend>imu_sensor_broadcaster</exec_depend>
|
||||
|
||||
<export>
|
||||
<build_type>ament_cmake</build_type>
|
||||
</export>
|
||||
|
||||
</package>
|
|
@ -0,0 +1,973 @@
|
|||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<!-- =================================================================================== -->
|
||||
<!-- | This document was autogenerated by xacro from robot.xacro | -->
|
||||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
<!-- =================================================================================== -->
|
||||
<robot name="a1">
|
||||
<!-- dynamics inertial value -->
|
||||
<!-- trunk -->
|
||||
<!-- <xacro:property name="trunk_mass" value="5.660"/>
|
||||
<xacro:property name="trunk_com_x" value="0.012731"/>
|
||||
<xacro:property name="trunk_com_y" value="0.002186"/>
|
||||
<xacro:property name="trunk_com_z" value="0.000515"/>
|
||||
<xacro:property name="trunk_ixx" value="0.016839930"/>
|
||||
<xacro:property name="trunk_ixy" value="0.000083902"/>
|
||||
<xacro:property name="trunk_ixz" value="0.000597679"/>
|
||||
<xacro:property name="trunk_iyy" value="0.056579028"/>
|
||||
<xacro:property name="trunk_iyz" value="0.000025134"/>
|
||||
<xacro:property name="trunk_izz" value="0.064713601"/> -->
|
||||
<material name="black">
|
||||
<color rgba="0.0 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="blue">
|
||||
<color rgba="0.0 0.0 0.8 1.0"/>
|
||||
</material>
|
||||
<material name="green">
|
||||
<color rgba="0.0 0.8 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="grey">
|
||||
<color rgba="0.2 0.2 0.2 1.0"/>
|
||||
</material>
|
||||
<material name="silver">
|
||||
<color rgba="0.913725490196 0.913725490196 0.847058823529 1.0"/>
|
||||
</material>
|
||||
<material name="orange">
|
||||
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
|
||||
</material>
|
||||
<material name="brown">
|
||||
<color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
|
||||
</material>
|
||||
<material name="red">
|
||||
<color rgba="0.8 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="white">
|
||||
<color rgba="1.0 1.0 1.0 1.0"/>
|
||||
</material>
|
||||
<!-- ros_control plugin -->
|
||||
<gazebo>
|
||||
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
|
||||
<robotNamespace>/a1_gazebo</robotNamespace>
|
||||
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
<!-- Show the trajectory of trunk center. -->
|
||||
<gazebo>
|
||||
<plugin filename="libLinkPlot3DPlugin.so" name="3dplotTrunk">
|
||||
<frequency>10</frequency>
|
||||
<plot>
|
||||
<link>base</link>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<material>Gazebo/Yellow</material>
|
||||
</plot>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
<!-- Show the trajectory of foot. You can add another trajectory about another foot. -->
|
||||
<gazebo>
|
||||
<plugin filename="libLinkPlot3DPlugin.so" name="3dplot">
|
||||
<frequency>1000</frequency>
|
||||
<plot>
|
||||
<link>FR_calf</link>
|
||||
<pose>0 0 -0.2 0 0 0</pose>
|
||||
<material>Gazebo/Yellow</material>
|
||||
</plot>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
<gazebo>
|
||||
<plugin filename="libgazebo_ros_force.so" name="gazebo_ros_force">
|
||||
<bodyName>trunk</bodyName>
|
||||
<topicName>/apply_force/trunk</topicName>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
<gazebo reference="imu_link">
|
||||
<gravity>true</gravity>
|
||||
<sensor name="imu_sensor" type="imu">
|
||||
<always_on>true</always_on>
|
||||
<update_rate>1000</update_rate>
|
||||
<visualize>true</visualize>
|
||||
<topic>__default_topic__</topic>
|
||||
<plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
|
||||
<topicName>trunk_imu</topicName>
|
||||
<bodyName>imu_link</bodyName>
|
||||
<updateRateHZ>1000.0</updateRateHZ>
|
||||
<gaussianNoise>0.0</gaussianNoise>
|
||||
<xyzOffset>0 0 0</xyzOffset>
|
||||
<rpyOffset>0 0 0</rpyOffset>
|
||||
<frameName>imu_link</frameName>
|
||||
</plugin>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<!-- Foot contacts. -->
|
||||
<gazebo reference="FR_calf">
|
||||
<sensor name="FR_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin filename="libunitreeFootContactPlugin.so" name="contactPlugin"/>
|
||||
<contact>
|
||||
<collision>FR_calf_fixed_joint_lump__FR_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_calf">
|
||||
<sensor name="FL_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin filename="libunitreeFootContactPlugin.so" name="contactPlugin"/>
|
||||
<contact>
|
||||
<collision>FL_calf_fixed_joint_lump__FL_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_calf">
|
||||
<sensor name="RR_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin filename="libunitreeFootContactPlugin.so" name="contactPlugin"/>
|
||||
<contact>
|
||||
<collision>RR_calf_fixed_joint_lump__RR_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_calf">
|
||||
<sensor name="RL_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin filename="libunitreeFootContactPlugin.so" name="contactPlugin"/>
|
||||
<contact>
|
||||
<collision>RL_calf_fixed_joint_lump__RL_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<!-- Visualization of Foot contacts. -->
|
||||
<gazebo reference="FR_foot">
|
||||
<visual>
|
||||
<plugin filename="libunitreeDrawForcePlugin.so" name="drawForcePlugin">
|
||||
<topicName>FR_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_foot">
|
||||
<visual>
|
||||
<plugin filename="libunitreeDrawForcePlugin.so" name="drawForcePlugin">
|
||||
<topicName>FL_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_foot">
|
||||
<visual>
|
||||
<plugin filename="libunitreeDrawForcePlugin.so" name="drawForcePlugin">
|
||||
<topicName>RR_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_foot">
|
||||
<visual>
|
||||
<plugin filename="libunitreeDrawForcePlugin.so" name="drawForcePlugin">
|
||||
<topicName>RL_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
<gazebo reference="base">
|
||||
<material>Gazebo/Green</material>
|
||||
<turnGravityOff>false</turnGravityOff>
|
||||
</gazebo>
|
||||
<gazebo reference="trunk">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="stick_link">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/White</material>
|
||||
</gazebo>
|
||||
<gazebo reference="imu_link">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/Red</material>
|
||||
</gazebo>
|
||||
<!-- FL leg -->
|
||||
<gazebo reference="FL_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<!-- FR leg -->
|
||||
<gazebo reference="FR_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="FR_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="FR_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="FR_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<!-- RL leg -->
|
||||
<gazebo reference="RL_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<!-- RR leg -->
|
||||
<gazebo reference="RR_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<!-- <xacro:include filename="$(find a1_gazebo)/launch/stairs.urdf.xacro"/> -->
|
||||
<!-- <xacro:stairs stairs="15" xpos="0" ypos="0" zpos="0" /> -->
|
||||
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
|
||||
<!-- <xacro:if value="$(arg DEBUG)">
|
||||
<link name="world"/>
|
||||
<joint name="base_static_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="world"/>
|
||||
<child link="base"/>
|
||||
</joint>
|
||||
</xacro:if> -->
|
||||
<link name="base">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name="floating_base" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="base"/>
|
||||
<child link="trunk"/>
|
||||
</joint>
|
||||
<link name="trunk">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/trunk.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.267 0.194 0.114"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0 0.0041 -0.0005"/>
|
||||
<mass value="6.0"/>
|
||||
<inertia ixx="0.0158533" ixy="-3.66e-05" ixz="-6.11e-05" iyy="0.0377999" iyz="-2.75e-05" izz="0.0456542"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<parent link="trunk"/>
|
||||
<child link="imu_link"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</joint>
|
||||
<link name="imu_link">
|
||||
<inertial>
|
||||
<mass value="0.001"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="red"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size=".001 .001 .001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="FR_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.1805 -0.047 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="FR_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-0.802851455917" upper="0.802851455917" velocity="21"/>
|
||||
</joint>
|
||||
<link name="FR_hip">
|
||||
<visual>
|
||||
<origin rpy="3.14159265359 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003311 -0.000635 3.1e-05"/>
|
||||
<mass value="0.696"/>
|
||||
<inertia ixx="0.000469246" ixy="9.409e-06" ixz="-3.42e-07" iyy="0.00080749" iyz="4.66e-07" izz="0.000552929"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 -0.081 0"/>
|
||||
<parent link="FR_hip"/>
|
||||
<child link="FR_thigh_shoulder"/>
|
||||
</joint>
|
||||
<!-- this link is only for collision -->
|
||||
<link name="FR_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.032" radius="0.041"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="FR_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 -0.0838 0"/>
|
||||
<parent link="FR_hip"/>
|
||||
<child link="FR_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-1.0471975512" upper="4.18879020479" velocity="21"/>
|
||||
</joint>
|
||||
<link name="FR_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/thigh_mirror.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.0245 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003237 0.022327 -0.027326"/>
|
||||
<mass value="1.013"/>
|
||||
<inertia ixx="0.005529065" ixy="-4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="-2.2448e-05" izz="0.001367788"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="FR_thigh"/>
|
||||
<child link="FR_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-2.69653369433" upper="-0.916297857297" velocity="21"/>
|
||||
</joint>
|
||||
<link name="FR_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/calf.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
|
||||
<mass value="0.166"/>
|
||||
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="FR_calf"/>
|
||||
<child link="FR_foot"/>
|
||||
</joint>
|
||||
<link name="FR_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.01"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="FR_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FR_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FR_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="FR_thigh_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FR_thigh_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FR_thigh_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="FR_calf_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FR_calf_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FR_calf_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<joint name="FL_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.1805 0.047 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="FL_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-0.802851455917" upper="0.802851455917" velocity="21"/>
|
||||
</joint>
|
||||
<link name="FL_hip">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003311 0.000635 3.1e-05"/>
|
||||
<mass value="0.696"/>
|
||||
<inertia ixx="0.000469246" ixy="-9.409e-06" ixz="-3.42e-07" iyy="0.00080749" iyz="-4.66e-07" izz="0.000552929"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0.081 0"/>
|
||||
<parent link="FL_hip"/>
|
||||
<child link="FL_thigh_shoulder"/>
|
||||
</joint>
|
||||
<!-- this link is only for collision -->
|
||||
<link name="FL_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.032" radius="0.041"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="FL_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0.0838 0"/>
|
||||
<parent link="FL_hip"/>
|
||||
<child link="FL_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-1.0471975512" upper="4.18879020479" velocity="21"/>
|
||||
</joint>
|
||||
<link name="FL_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/thigh.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.0245 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003237 -0.022327 -0.027326"/>
|
||||
<mass value="1.013"/>
|
||||
<inertia ixx="0.005529065" ixy="4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="2.2448e-05" izz="0.001367788"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="FL_thigh"/>
|
||||
<child link="FL_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-2.69653369433" upper="-0.916297857297" velocity="21"/>
|
||||
</joint>
|
||||
<link name="FL_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/calf.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
|
||||
<mass value="0.166"/>
|
||||
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="FL_calf"/>
|
||||
<child link="FL_foot"/>
|
||||
</joint>
|
||||
<link name="FL_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.01"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="FL_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FL_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FL_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="FL_thigh_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FL_thigh_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FL_thigh_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="FL_calf_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FL_calf_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FL_calf_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<joint name="RR_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="-0.1805 -0.047 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="RR_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-0.802851455917" upper="0.802851455917" velocity="21"/>
|
||||
</joint>
|
||||
<link name="RR_hip">
|
||||
<visual>
|
||||
<origin rpy="3.14159265359 3.14159265359 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.003311 -0.000635 3.1e-05"/>
|
||||
<mass value="0.696"/>
|
||||
<inertia ixx="0.000469246" ixy="-9.409e-06" ixz="3.42e-07" iyy="0.00080749" iyz="4.66e-07" izz="0.000552929"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 -0.081 0"/>
|
||||
<parent link="RR_hip"/>
|
||||
<child link="RR_thigh_shoulder"/>
|
||||
</joint>
|
||||
<!-- this link is only for collision -->
|
||||
<link name="RR_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.032" radius="0.041"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="RR_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 -0.0838 0"/>
|
||||
<parent link="RR_hip"/>
|
||||
<child link="RR_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-1.0471975512" upper="4.18879020479" velocity="21"/>
|
||||
</joint>
|
||||
<link name="RR_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/thigh_mirror.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.0245 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003237 0.022327 -0.027326"/>
|
||||
<mass value="1.013"/>
|
||||
<inertia ixx="0.005529065" ixy="-4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="-2.2448e-05" izz="0.001367788"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="RR_thigh"/>
|
||||
<child link="RR_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-2.69653369433" upper="-0.916297857297" velocity="21"/>
|
||||
</joint>
|
||||
<link name="RR_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/calf.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
|
||||
<mass value="0.166"/>
|
||||
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="RR_calf"/>
|
||||
<child link="RR_foot"/>
|
||||
</joint>
|
||||
<link name="RR_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.01"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="RR_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RR_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RR_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="RR_thigh_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RR_thigh_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RR_thigh_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="RR_calf_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RR_calf_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RR_calf_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<joint name="RL_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="-0.1805 0.047 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="RL_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-0.802851455917" upper="0.802851455917" velocity="21"/>
|
||||
</joint>
|
||||
<link name="RL_hip">
|
||||
<visual>
|
||||
<origin rpy="0 3.14159265359 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.003311 0.000635 3.1e-05"/>
|
||||
<mass value="0.696"/>
|
||||
<inertia ixx="0.000469246" ixy="9.409e-06" ixz="3.42e-07" iyy="0.00080749" iyz="-4.66e-07" izz="0.000552929"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0.081 0"/>
|
||||
<parent link="RL_hip"/>
|
||||
<child link="RL_thigh_shoulder"/>
|
||||
</joint>
|
||||
<!-- this link is only for collision -->
|
||||
<link name="RL_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.032" radius="0.041"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="RL_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0.0838 0"/>
|
||||
<parent link="RL_hip"/>
|
||||
<child link="RL_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-1.0471975512" upper="4.18879020479" velocity="21"/>
|
||||
</joint>
|
||||
<link name="RL_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/thigh.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.0245 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003237 -0.022327 -0.027326"/>
|
||||
<mass value="1.013"/>
|
||||
<inertia ixx="0.005529065" ixy="4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="2.2448e-05" izz="0.001367788"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="RL_thigh"/>
|
||||
<child link="RL_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-2.69653369433" upper="-0.916297857297" velocity="21"/>
|
||||
</joint>
|
||||
<link name="RL_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/calf.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
|
||||
<mass value="0.166"/>
|
||||
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="RL_calf"/>
|
||||
<child link="RL_foot"/>
|
||||
</joint>
|
||||
<link name="RL_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.01"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="RL_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RL_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RL_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="RL_thigh_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RL_thigh_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RL_thigh_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="RL_calf_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RL_calf_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RL_calf_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<!-- <xacro:stairs stairs="15" xpos="0" ypos="2.0" zpos="0" /> -->
|
||||
</robot>
|
||||
|
|
@ -0,0 +1,104 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<!-- Constants for robot dimensions -->
|
||||
<xacro:property name="PI" value="3.1415926535897931"/>
|
||||
<xacro:property name="stick_mass" value="0.00001"/>
|
||||
|
||||
<!-- simplified collision value -->
|
||||
<xacro:property name="trunk_width" value="0.194"/>
|
||||
<xacro:property name="trunk_length" value="0.267"/>
|
||||
<xacro:property name="trunk_height" value="0.114"/>
|
||||
<xacro:property name="hip_radius" value="0.046"/>
|
||||
<xacro:property name="hip_length" value="0.04"/>
|
||||
<xacro:property name="thigh_shoulder_radius" value="0.041"/>
|
||||
<xacro:property name="thigh_shoulder_length" value="0.032"/>
|
||||
<xacro:property name="thigh_width" value="0.0245"/>
|
||||
<xacro:property name="thigh_height" value="0.034"/>
|
||||
<xacro:property name="calf_width" value="0.016"/>
|
||||
<xacro:property name="calf_height" value="0.016"/>
|
||||
<xacro:property name="foot_radius" value="0.02"/>
|
||||
<xacro:property name="stick_radius" value="0.01"/>
|
||||
<xacro:property name="stick_length" value="0.2"/>
|
||||
|
||||
<!-- kinematic value -->
|
||||
<xacro:property name="thigh_offset" value="0.0838"/>
|
||||
<xacro:property name="thigh_length" value="0.2"/>
|
||||
<xacro:property name="calf_length" value="0.2"/>
|
||||
|
||||
<!-- leg offset from trunk center value -->
|
||||
<xacro:property name="leg_offset_x" value="0.1805"/>
|
||||
<xacro:property name="leg_offset_y" value="0.047"/>
|
||||
<xacro:property name="trunk_offset_z" value="0.01675"/>
|
||||
<xacro:property name="hip_offset" value="0.065"/>
|
||||
|
||||
<!-- joint limits -->
|
||||
<xacro:property name="damping" value="0"/>
|
||||
<xacro:property name="friction" value="0"/>
|
||||
<xacro:property name="hip_max" value="46"/>
|
||||
<xacro:property name="hip_min" value="-46"/>
|
||||
<xacro:property name="hip_velocity_max" value="21"/>
|
||||
<xacro:property name="hip_torque_max" value="33.5"/>
|
||||
<xacro:property name="thigh_max" value="240"/>
|
||||
<xacro:property name="thigh_min" value="-60"/>
|
||||
<xacro:property name="thigh_velocity_max" value="21"/>
|
||||
<xacro:property name="thigh_torque_max" value="33.5"/>
|
||||
<xacro:property name="calf_max" value="-52.5"/>
|
||||
<xacro:property name="calf_min" value="-154.5"/>
|
||||
<xacro:property name="calf_velocity_max" value="21"/>
|
||||
<xacro:property name="calf_torque_max" value="33.5"/>
|
||||
|
||||
<!-- dynamics inertial value total 13.9kg -->
|
||||
<!-- trunk -->
|
||||
<xacro:property name="trunk_mass" value="6.0"/>
|
||||
<xacro:property name="trunk_com_x" value="0.0000"/>
|
||||
<xacro:property name="trunk_com_y" value="0.0041"/>
|
||||
<xacro:property name="trunk_com_z" value="-0.0005"/>
|
||||
<xacro:property name="trunk_ixx" value="0.0158533"/>
|
||||
<xacro:property name="trunk_ixy" value="-0.0000366"/>
|
||||
<xacro:property name="trunk_ixz" value="-0.0000611"/>
|
||||
<xacro:property name="trunk_iyy" value="0.0377999"/>
|
||||
<xacro:property name="trunk_iyz" value="-0.0000275"/>
|
||||
<xacro:property name="trunk_izz" value="0.0456542"/>
|
||||
|
||||
<!-- hip (left front) -->
|
||||
<xacro:property name="hip_mass" value="0.595"/>
|
||||
<xacro:property name="hip_com_x" value="-0.003875"/>
|
||||
<xacro:property name="hip_com_y" value="0.001622"/>
|
||||
<xacro:property name="hip_com_z" value="0.000042"/>
|
||||
<xacro:property name="hip_ixx" value="0.000402747"/>
|
||||
<xacro:property name="hip_ixy" value="-0.000008709"/>
|
||||
<xacro:property name="hip_ixz" value="-0.000000297"/>
|
||||
<xacro:property name="hip_iyy" value="0.000691123"/>
|
||||
<xacro:property name="hip_iyz" value="-0.000000545"/>
|
||||
<xacro:property name="hip_izz" value="0.000487919"/>
|
||||
|
||||
<!-- thigh -->
|
||||
<xacro:property name="thigh_mass" value="0.888"/>
|
||||
<xacro:property name="thigh_com_x" value="-0.003574"/>
|
||||
<xacro:property name="thigh_com_y" value="-0.019529"/>
|
||||
<xacro:property name="thigh_com_z" value="-0.030323"/>
|
||||
<xacro:property name="thigh_ixx" value="0.005251806"/>
|
||||
<xacro:property name="thigh_ixy" value="-0.000002168"/>
|
||||
<xacro:property name="thigh_ixz" value="0.000346889"/>
|
||||
<xacro:property name="thigh_iyy" value="0.005000475"/>
|
||||
<xacro:property name="thigh_iyz" value="-0.000028174"/>
|
||||
<xacro:property name="thigh_izz" value="0.001110200"/>
|
||||
|
||||
<!-- calf -->
|
||||
<xacro:property name="calf_mass" value="0.151"/>
|
||||
<xacro:property name="calf_com_x" value="0.007105"/>
|
||||
<xacro:property name="calf_com_y" value="-0.000239"/>
|
||||
<xacro:property name="calf_com_z" value="-0.096933"/>
|
||||
<xacro:property name="calf_ixx" value="0.002344758"/>
|
||||
<xacro:property name="calf_ixy" value="0.0"/>
|
||||
<xacro:property name="calf_ixz" value="-0.000141275"/>
|
||||
<xacro:property name="calf_iyy" value="0.002360755"/>
|
||||
<xacro:property name="calf_iyz" value="0.0"/>
|
||||
<xacro:property name="calf_izz" value="0.000031158"/>
|
||||
|
||||
<!-- foot -->
|
||||
<xacro:property name="foot_mass" value="0.06"/>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,266 @@
|
|||
<?xml version="1.0"?>
|
||||
<robot>
|
||||
<!-- ros_control plugin -->
|
||||
<gazebo>
|
||||
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
||||
<robotNamespace>/a1_gazebo</robotNamespace>
|
||||
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<!-- Show the trajectory of trunk center. -->
|
||||
<gazebo>
|
||||
<plugin name="3dplot" filename="libLinkPlot3DPlugin.so">
|
||||
<frequency>10</frequency>
|
||||
<plot>
|
||||
<link>base</link>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<material>Gazebo/Yellow</material>
|
||||
</plot>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<!-- Show the trajectory of foot. You can add another trajectory about another foot. -->
|
||||
<!-- <gazebo>
|
||||
<plugin name="3dplot" filename="libLinkPlot3DPlugin.so">
|
||||
<frequency>100</frequency>
|
||||
<plot>
|
||||
<link>FL_foot</link>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<material>Gazebo/Green</material>
|
||||
</plot>
|
||||
</plugin>
|
||||
</gazebo> -->
|
||||
|
||||
<gazebo>
|
||||
<plugin filename="libgazebo_ros_force.so" name="gazebo_ros_force">
|
||||
<bodyName>trunk</bodyName>
|
||||
<topicName>/apply_force/trunk</topicName>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="imu_link">
|
||||
<gravity>true</gravity>
|
||||
<sensor name="imu_sensor" type="imu">
|
||||
<always_on>true</always_on>
|
||||
<update_rate>1000</update_rate>
|
||||
<visualize>true</visualize>
|
||||
<topic>__default_topic__</topic>
|
||||
<plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
|
||||
<topicName>trunk_imu</topicName>
|
||||
<bodyName>imu_link</bodyName>
|
||||
<updateRateHZ>1000.0</updateRateHZ>
|
||||
<gaussianNoise>0.0</gaussianNoise>
|
||||
<xyzOffset>0 0 0</xyzOffset>
|
||||
<rpyOffset>0 0 0</rpyOffset>
|
||||
<frameName>imu_link</frameName>
|
||||
</plugin>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
|
||||
<!-- Foot contacts. -->
|
||||
<gazebo reference="FR_calf">
|
||||
<sensor name="FR_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin name="contactPlugin" filename="libunitreeFootContactPlugin.so"/>
|
||||
<contact>
|
||||
<collision>FR_calf_fixed_joint_lump__FR_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_calf">
|
||||
<sensor name="FL_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin name="contactPlugin" filename="libunitreeFootContactPlugin.so"/>
|
||||
<contact>
|
||||
<collision>FL_calf_fixed_joint_lump__FL_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_calf">
|
||||
<sensor name="RR_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin name="contactPlugin" filename="libunitreeFootContactPlugin.so"/>
|
||||
<contact>
|
||||
<collision>RR_calf_fixed_joint_lump__RR_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_calf">
|
||||
<sensor name="RL_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin name="contactPlugin" filename="libunitreeFootContactPlugin.so"/>
|
||||
<contact>
|
||||
<collision>RL_calf_fixed_joint_lump__RL_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
|
||||
<!-- Visualization of Foot contacts. -->
|
||||
<gazebo reference="FR_foot">
|
||||
<visual>
|
||||
<plugin name="drawForcePlugin" filename="libunitreeDrawForcePlugin.so">
|
||||
<topicName>FR_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_foot">
|
||||
<visual>
|
||||
<plugin name="drawForcePlugin" filename="libunitreeDrawForcePlugin.so">
|
||||
<topicName>FL_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_foot">
|
||||
<visual>
|
||||
<plugin name="drawForcePlugin" filename="libunitreeDrawForcePlugin.so">
|
||||
<topicName>RR_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_foot">
|
||||
<visual>
|
||||
<plugin name="drawForcePlugin" filename="libunitreeDrawForcePlugin.so">
|
||||
<topicName>RL_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="base">
|
||||
<material>Gazebo/Green</material>
|
||||
<turnGravityOff>false</turnGravityOff>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="trunk">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="stick_link">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/White</material>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="imu_link">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/Red</material>
|
||||
</gazebo>
|
||||
|
||||
<!-- FL leg -->
|
||||
<gazebo reference="FL_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
<!-- FR leg -->
|
||||
<gazebo reference="FR_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="FR_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="FR_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="FR_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
<!-- RL leg -->
|
||||
<gazebo reference="RL_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
<!-- RR leg -->
|
||||
<gazebo reference="RR_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,176 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:include filename="$(find a1_description)/xacro/transmission.xacro"/>
|
||||
|
||||
<xacro:macro name="leg" params="name mirror mirror_dae front_hind front_hind_dae *origin">
|
||||
|
||||
<joint name="${name}_hip_joint" type="revolute">
|
||||
<xacro:insert_block name="origin"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="${name}_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="${damping}" friction="${friction}"/>
|
||||
<xacro:if value="${(mirror_dae == True)}">
|
||||
<limit effort="${hip_torque_max}" velocity="${hip_velocity_max}" lower="${hip_min*PI/180.0}" upper="${hip_max*PI/180.0}"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == False)}">
|
||||
<limit effort="${hip_torque_max}" velocity="${hip_velocity_max}" lower="${-hip_max*PI/180.0}" upper="${-hip_min*PI/180.0}"/>
|
||||
</xacro:if>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_hip">
|
||||
<visual>
|
||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == True)}">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == True)}">
|
||||
<origin rpy="${PI} 0 0" xyz="0 0 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == False)}">
|
||||
<origin rpy="0 ${PI} 0" xyz="0 0 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == False)}">
|
||||
<origin rpy="${PI} ${PI} 0" xyz="0 0 0"/>
|
||||
</xacro:if>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/hip.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${hip_length}" radius="${hip_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${hip_com_x*front_hind} ${hip_com_y*mirror} ${hip_com_z}"/>
|
||||
<mass value="${hip_mass}"/>
|
||||
<inertia
|
||||
ixx="${hip_ixx}" ixy="${hip_ixy*mirror*front_hind}" ixz="${hip_ixz*front_hind}"
|
||||
iyy="${hip_iyy}" iyz="${hip_iyz*mirror}"
|
||||
izz="${hip_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
|
||||
<parent link="${name}_hip"/>
|
||||
<child link="${name}_thigh_shoulder"/>
|
||||
</joint>
|
||||
|
||||
<!-- this link is only for collision -->
|
||||
<link name="${name}_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 ${thigh_offset*mirror} 0"/>
|
||||
<parent link="${name}_hip"/>
|
||||
<child link="${name}_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="${damping}" friction="${friction}"/>
|
||||
<limit effort="${thigh_torque_max}" velocity="${thigh_velocity_max}" lower="${thigh_min*PI/180.0}" upper="${thigh_max*PI/180.0}"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<xacro:if value="${mirror_dae == True}">
|
||||
<mesh filename="package://a1_description/meshes/thigh.dae" scale="1 1 1"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${mirror_dae == False}">
|
||||
<mesh filename="package://a1_description/meshes/thigh_mirror.dae" scale="1 1 1"/>
|
||||
</xacro:if>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 ${-thigh_length/2.0}"/>
|
||||
<geometry>
|
||||
<box size="${thigh_length} ${thigh_width} ${thigh_height}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${thigh_com_x} ${thigh_com_y*mirror} ${thigh_com_z}"/>
|
||||
<mass value="${thigh_mass}"/>
|
||||
<inertia
|
||||
ixx="${thigh_ixx}" ixy="${thigh_ixy*mirror}" ixz="${thigh_ixz}"
|
||||
iyy="${thigh_iyy}" iyz="${thigh_iyz*mirror}"
|
||||
izz="${thigh_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 ${-thigh_length}"/>
|
||||
<parent link="${name}_thigh"/>
|
||||
<child link="${name}_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="${damping}" friction="${friction}"/>
|
||||
<limit effort="${calf_torque_max}" velocity="${calf_velocity_max}" lower="${calf_min*PI/180.0}" upper="${calf_max*PI/180.0}"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/calf.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 ${-calf_length/2.0}"/>
|
||||
<geometry>
|
||||
<box size="${calf_length} ${calf_width} ${calf_height}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${calf_com_x} ${calf_com_y} ${calf_com_z}"/>
|
||||
<mass value="${calf_mass}"/>
|
||||
<inertia
|
||||
ixx="${calf_ixx}" ixy="${calf_ixy}" ixz="${calf_ixz}"
|
||||
iyy="${calf_iyy}" iyz="${calf_iyz}"
|
||||
izz="${calf_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 ${-(calf_length)}"/>
|
||||
<parent link="${name}_calf"/>
|
||||
<child link="${name}_foot"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="${foot_radius-0.01}"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="${foot_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="${foot_mass}"/>
|
||||
<inertia
|
||||
ixx="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}" ixy="0.0" ixz="0.0"
|
||||
iyy="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}" iyz="0.0"
|
||||
izz="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<xacro:leg_transmission name="${name}"/>
|
||||
</xacro:macro>
|
||||
</robot>
|
|
@ -0,0 +1,40 @@
|
|||
<?xml version="1.0"?>
|
||||
<robot>
|
||||
|
||||
<material name="black">
|
||||
<color rgba="0.0 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="blue">
|
||||
<color rgba="0.0 0.0 0.8 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="green">
|
||||
<color rgba="0.0 0.8 0.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="grey">
|
||||
<color rgba="0.2 0.2 0.2 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="silver">
|
||||
<color rgba="${233/255} ${233/255} ${216/255} 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="orange">
|
||||
<color rgba="${255/255} ${108/255} ${10/255} 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="brown">
|
||||
<color rgba="${222/255} ${207/255} ${195/255} 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="red">
|
||||
<color rgba="0.8 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="white">
|
||||
<color rgba="1.0 1.0 1.0 1.0"/>
|
||||
</material>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,143 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot name="a1" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:arg name="DEBUG" default="false"/>
|
||||
|
||||
<xacro:include filename="$(find a1_description)/xacro/const.xacro"/>
|
||||
<xacro:include filename="$(find a1_description)/xacro/materials.xacro"/>
|
||||
<xacro:include filename="$(find a1_description)/xacro/leg.xacro"/>
|
||||
<xacro:include filename="$(find a1_description)/xacro/stairs.xacro"/>
|
||||
<xacro:include filename="$(find a1_description)/xacro/ros2_control.xacro"/>
|
||||
|
||||
<!-- <xacro:stairs stairs="15" xpos="0" ypos="0" zpos="0" /> -->
|
||||
|
||||
<!-- Rollover Protection mode will add an additional stick on the top, use "true" or "false" to switch it. -->
|
||||
<xacro:property name="rolloverProtection" value="false"/>
|
||||
|
||||
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
|
||||
<xacro:if value="$(arg DEBUG)">
|
||||
<link name="world"/>
|
||||
<joint name="base_static_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="world"/>
|
||||
<child link="base"/>
|
||||
</joint>
|
||||
</xacro:if>
|
||||
|
||||
<link name="base">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name="floating_base" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="base"/>
|
||||
<child link="trunk"/>
|
||||
</joint>
|
||||
|
||||
<link name="trunk">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://a1_description/meshes/trunk.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="${trunk_length} ${trunk_width} ${trunk_height}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${trunk_com_x} ${trunk_com_y} ${trunk_com_z}"/>
|
||||
<mass value="${trunk_mass}"/>
|
||||
<inertia
|
||||
ixx="${trunk_ixx}" ixy="${trunk_ixy}" ixz="${trunk_ixz}"
|
||||
iyy="${trunk_iyy}" iyz="${trunk_iyz}"
|
||||
izz="${trunk_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<xacro:if value="${(rolloverProtection == 'true')}">
|
||||
<joint name="stick_joint" type="fixed">
|
||||
<parent link="trunk"/>
|
||||
<child link="stick_link"/>
|
||||
<origin rpy="0 0 0" xyz="${0.18} 0 ${stick_length/2.0+0.08}"/>
|
||||
</joint>
|
||||
|
||||
<link name="stick_link">
|
||||
<visual>
|
||||
<geometry>
|
||||
<cylinder length="${stick_length}" radius="${stick_radius}"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<cylinder length="${stick_length}" radius="${stick_radius}"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="${stick_mass}"/>
|
||||
<inertia
|
||||
ixx="${stick_mass / 2.0 * (stick_radius*stick_radius)}" ixy="0.0" ixz="0.0"
|
||||
iyy="${stick_mass / 12.0 * (3*stick_radius*stick_radius + stick_length*stick_length)}" iyz="0.0"
|
||||
izz="${stick_mass / 12.0 * (3*stick_radius*stick_radius + stick_length*stick_length)}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
</xacro:if>
|
||||
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<parent link="trunk"/>
|
||||
<child link="imu_link"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
<link name="imu_link">
|
||||
<inertial>
|
||||
<mass value="0.001"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="red"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size=".001 .001 .001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<xacro:leg name="FR" mirror="-1" mirror_dae="False" front_hind="1" front_hind_dae="True">
|
||||
<origin rpy="0 0 0" xyz="${leg_offset_x} ${-leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<xacro:leg name="FL" mirror="1" mirror_dae="True" front_hind="1" front_hind_dae="True">
|
||||
<origin rpy="0 0 0" xyz="${leg_offset_x} ${leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<xacro:leg name="RR" mirror="-1" mirror_dae="False" front_hind="-1" front_hind_dae="False">
|
||||
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${-leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<xacro:leg name="RL" mirror="1" mirror_dae="True" front_hind="-1" front_hind_dae="False">
|
||||
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<!-- <xacro:stairs stairs="15" xpos="0" ypos="2.0" zpos="0" /> -->
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,176 @@
|
|||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<ros2_control name="UnitreeSystem" type="system">
|
||||
|
||||
<hardware>
|
||||
<plugin>hardware_unitree_mujoco/HardwareUnitree</plugin>
|
||||
</hardware>
|
||||
|
||||
<joint name="FR_hip_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="FR_thigh_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="FR_calf_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="FL_hip_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="FL_thigh_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="FL_calf_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="RR_hip_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="RR_thigh_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="RR_calf_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="RL_hip_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="RL_thigh_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="RL_calf_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<sensor name="imu_sensor">
|
||||
<state_interface name="orientation.w"/>
|
||||
<state_interface name="orientation.x"/>
|
||||
<state_interface name="orientation.y"/>
|
||||
<state_interface name="orientation.z"/>
|
||||
<state_interface name="angular_velocity.x"/>
|
||||
<state_interface name="angular_velocity.y"/>
|
||||
<state_interface name="angular_velocity.z"/>
|
||||
<state_interface name="linear_acceleration.x"/>
|
||||
<state_interface name="linear_acceleration.y"/>
|
||||
<state_interface name="linear_acceleration.z"/>
|
||||
</sensor>
|
||||
|
||||
<sensor name="foot_force">
|
||||
<state_interface name="FR"/>
|
||||
<state_interface name="FL"/>
|
||||
<state_interface name="RR"/>
|
||||
<state_interface name="RL"/>
|
||||
</sensor>
|
||||
|
||||
</ros2_control>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,46 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:property name="stair_length" value="0.640" />
|
||||
<xacro:property name="stair_width" value="0.310" />
|
||||
<xacro:property name="stair_height" value="0.170" />
|
||||
|
||||
<xacro:macro name="stairs" params="stairs xpos ypos zpos">
|
||||
|
||||
<joint name="stair_joint_origin" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="world"/>
|
||||
<child link="stair_link_${stairs}"/>
|
||||
</joint>
|
||||
|
||||
<link name="stair_link_${stairs}">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="${stair_length} ${stair_width} ${stair_height}"/>
|
||||
</geometry>
|
||||
<material name="grey"/>
|
||||
<origin rpy="0 0 0" xyz="${xpos} ${ypos} ${zpos}"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="${stair_length} ${stair_width} ${stair_height}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.80"/>
|
||||
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<xacro:if value="${stairs}">
|
||||
<xacro:stairs stairs="${stairs-1}" xpos="0" ypos="${ypos-stair_width/2}" zpos="${zpos+stair_height}"/>
|
||||
<joint name="stair_joint_${stairs}" type="fixed">
|
||||
<parent link="stair_link_${stairs}"/>
|
||||
<child link="stair_link_${stairs-1}"/>
|
||||
</joint>
|
||||
</xacro:if>
|
||||
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,42 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:macro name="leg_transmission" params="name">
|
||||
|
||||
<transmission name="${name}_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="${name}_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="${name}_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="${name}_thigh_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="${name}_thigh_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="${name}_thigh_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="${name}_calf_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="${name}_calf_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="${name}_calf_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
Loading…
Reference in New Issue