add deep robotics x30
This commit is contained in:
parent
a17b9448c3
commit
45fde17425
Binary file not shown.
After Width: | Height: | Size: 80 KiB |
|
@ -12,6 +12,7 @@ This folder contains the URDF and SRDF files for the quadruped robot.
|
|||
* [Cyberdog](xiaomi/cyberdog_description/)
|
||||
* Deep Robotics
|
||||
* [Lite 3](deep_robotics/lite3_description/)
|
||||
* [X30](deep_robotics/x30_description/)
|
||||
|
||||
## Steps to transfer urdf to Mujoco model
|
||||
|
||||
|
|
|
@ -0,0 +1,11 @@
|
|||
cmake_minimum_required(VERSION 3.8)
|
||||
project(x30_description)
|
||||
|
||||
find_package(ament_cmake REQUIRED)
|
||||
|
||||
install(
|
||||
DIRECTORY meshes xacro launch config urdf
|
||||
DESTINATION share/${PROJECT_NAME}/
|
||||
)
|
||||
|
||||
ament_package()
|
|
@ -0,0 +1,35 @@
|
|||
# DeepRobotics X30 Description
|
||||
This repository contains the urdf model of x30.
|
||||
|
||||
![x30](../../../.images/x30.png)
|
||||
|
||||
Tested environment:
|
||||
* Ubuntu 24.04
|
||||
* ROS2 Jazzy
|
||||
|
||||
## Build
|
||||
```bash
|
||||
cd ~/ros2_ws
|
||||
colcon build --packages-up-to x30_description --symlink-install
|
||||
```
|
||||
|
||||
## 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 x30_description visualize.launch.py
|
||||
```
|
||||
|
||||
## Launch ROS2 Control
|
||||
|
||||
### Gazebo Simulator
|
||||
* Unitree Guide Controller
|
||||
```bash
|
||||
source ~/ros2_ws/install/setup.bash
|
||||
ros2 launch x30_description gazebo_unitree_guide.launch.py
|
||||
```
|
||||
* Legged Gym Controller
|
||||
```bash
|
||||
source ~/ros2_ws/install/setup.bash
|
||||
ros2 launch x30_description gazebo_rl_control.launch.py
|
||||
```
|
|
@ -0,0 +1,143 @@
|
|||
# Controller Manager configuration
|
||||
controller_manager:
|
||||
ros__parameters:
|
||||
update_rate: 2000 # Hz
|
||||
|
||||
# Define the available controllers
|
||||
joint_state_broadcaster:
|
||||
type: joint_state_broadcaster/JointStateBroadcaster
|
||||
|
||||
imu_sensor_broadcaster:
|
||||
type: imu_sensor_broadcaster/IMUSensorBroadcaster
|
||||
|
||||
leg_pd_controller:
|
||||
type: leg_pd_controller/LegPdController
|
||||
|
||||
unitree_guide_controller:
|
||||
type: unitree_guide_controller/UnitreeGuideController
|
||||
|
||||
rl_quadruped_controller:
|
||||
type: rl_quadruped_controller/LeggedGymController
|
||||
|
||||
imu_sensor_broadcaster:
|
||||
ros__parameters:
|
||||
sensor_name: "imu_sensor"
|
||||
frame_id: "imu_link"
|
||||
|
||||
leg_pd_controller:
|
||||
ros__parameters:
|
||||
joints:
|
||||
- FR_HipX
|
||||
- FR_HipY
|
||||
- FR_Knee
|
||||
- FL_HipX
|
||||
- FL_HipY
|
||||
- FL_Knee
|
||||
- HR_HipX
|
||||
- HR_HipY
|
||||
- HR_Knee
|
||||
- HL_HipX
|
||||
- HL_HipY
|
||||
- HL_Knee
|
||||
|
||||
command_interfaces:
|
||||
- effort
|
||||
|
||||
state_interfaces:
|
||||
- position
|
||||
- velocity
|
||||
|
||||
unitree_guide_controller:
|
||||
ros__parameters:
|
||||
update_rate: 200 # Hz
|
||||
command_prefix: "leg_pd_controller"
|
||||
joints:
|
||||
- FR_HipX
|
||||
- FR_HipY
|
||||
- FR_Knee
|
||||
- FL_HipX
|
||||
- FL_HipY
|
||||
- FL_Knee
|
||||
- HR_HipX
|
||||
- HR_HipY
|
||||
- HR_Knee
|
||||
- HL_HipX
|
||||
- HL_HipY
|
||||
- HL_Knee
|
||||
|
||||
command_interfaces:
|
||||
- effort
|
||||
- position
|
||||
- velocity
|
||||
- kp
|
||||
- kd
|
||||
|
||||
state_interfaces:
|
||||
- effort
|
||||
- position
|
||||
- velocity
|
||||
|
||||
feet_names:
|
||||
- FR_FOOT
|
||||
- FL_FOOT
|
||||
- HR_FOOT
|
||||
- HL_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
|
||||
|
||||
rl_quadruped_controller:
|
||||
ros__parameters:
|
||||
update_rate: 200 # Hz
|
||||
config_folder: "/home/tlab-uav/ros2_ws/install/a1_description/share/a1_description/config/issacgym"
|
||||
command_prefix: "leg_pd_controller"
|
||||
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
|
||||
|
||||
imu_name: "imu_sensor"
|
||||
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
|
|
@ -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,76 @@
|
|||
# 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
|
||||
|
||||
rl_quadruped_controller:
|
||||
type: rl_quadruped_controller/LeggedGymController
|
||||
|
||||
imu_sensor_broadcaster:
|
||||
ros__parameters:
|
||||
sensor_name: "imu_sensor"
|
||||
frame_id: "imu_link"
|
||||
|
||||
|
||||
unitree_guide_controller:
|
||||
ros__parameters:
|
||||
update_rate: 500 # Hz
|
||||
joints:
|
||||
- FR_HipX
|
||||
- FR_HipY
|
||||
- FR_Knee
|
||||
- FL_HipX
|
||||
- FL_HipY
|
||||
- FL_Knee
|
||||
- HR_HipX
|
||||
- HR_HipY
|
||||
- HR_Knee
|
||||
- HL_HipX
|
||||
- HL_HipY
|
||||
- HL_Knee
|
||||
|
||||
command_interfaces:
|
||||
- effort
|
||||
- position
|
||||
- velocity
|
||||
- kp
|
||||
- kd
|
||||
|
||||
state_interfaces:
|
||||
- effort
|
||||
- position
|
||||
- velocity
|
||||
|
||||
feet_names:
|
||||
- FR_FOOT
|
||||
- FL_FOOT
|
||||
- HR_FOOT
|
||||
- HL_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
|
|
@ -0,0 +1,254 @@
|
|||
Panels:
|
||||
- Class: rviz_common/Displays
|
||||
Help Height: 138
|
||||
Name: Displays
|
||||
Property Tree Widget:
|
||||
Expanded:
|
||||
- /Global Options1
|
||||
- /Status1
|
||||
- /RobotModel1
|
||||
Splitter Ratio: 0.5
|
||||
Tree Height: 295
|
||||
- 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_FOOT:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_HIP:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_SHANK:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FL_THIGH:
|
||||
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_SHANK:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
FR_THIGH:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
HL_FOOT:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
HL_HIP:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
HL_SHANK:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
HL_THIGH:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
HR_FOOT:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
HR_HIP:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
HR_SHANK:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
HR_THIGH:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
INERTIA:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Link Tree Style: Links in Alphabetic Order
|
||||
TORSO:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
imu_link:
|
||||
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: TORSO
|
||||
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: 1.1684969663619995
|
||||
Enable Stereo Rendering:
|
||||
Stereo Eye Separation: 0.05999999865889549
|
||||
Stereo Focal Distance: 1
|
||||
Swap Stereo Eyes: false
|
||||
Value: false
|
||||
Focal Point:
|
||||
X: 0.011728689074516296
|
||||
Y: 0.011509218253195286
|
||||
Z: -0.10348724573850632
|
||||
Focal Shape Fixed Size: true
|
||||
Focal Shape Size: 0.05000000074505806
|
||||
Invert Z Axis: false
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.009999999776482582
|
||||
Pitch: 0.42539793252944946
|
||||
Target Frame: <Fixed Frame>
|
||||
Value: Orbit (rviz)
|
||||
Yaw: 0.6953961849212646
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
collapsed: false
|
||||
Height: 691
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: true
|
||||
QMainWindow State: 000000ff00000000fd000000040000000000000156000001f1fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005d00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003f000001f1000000cc00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000015d0000043cfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000700000043c000000a900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003bb0000005efc0100000002fb0000000800540069006d00650100000000000003bb0000026f00fffffffb0000000800540069006d006501000000000000045000000000000000000000025f000001f100000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
Selection:
|
||||
collapsed: false
|
||||
Time:
|
||||
collapsed: false
|
||||
Tool Properties:
|
||||
collapsed: false
|
||||
Views:
|
||||
collapsed: true
|
||||
Width: 955
|
||||
X: 773
|
||||
Y: 168
|
|
@ -0,0 +1,106 @@
|
|||
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.launch_description_sources import PythonLaunchDescriptionSource
|
||||
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 = "x30_description"
|
||||
|
||||
|
||||
def process_xacro():
|
||||
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={'GAZEBO': 'true'})
|
||||
return robot_description_config.toxml()
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
rviz_config_file = os.path.join(get_package_share_directory(package_description), "config", "visualize_urdf.rviz")
|
||||
|
||||
robot_description = process_xacro()
|
||||
|
||||
gz_spawn_entity = Node(
|
||||
package='ros_gz_sim',
|
||||
executable='create',
|
||||
output='screen',
|
||||
arguments=['-topic', 'robot_description', '-name',
|
||||
'x30', '-allow_renaming', 'true', '-z', '0.4'],
|
||||
)
|
||||
|
||||
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
|
||||
}
|
||||
],
|
||||
)
|
||||
|
||||
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"],
|
||||
)
|
||||
|
||||
leg_pd_controller = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=["leg_pd_controller",
|
||||
"--controller-manager", "/controller_manager"],
|
||||
)
|
||||
|
||||
unitree_guide_controller = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=["unitree_guide_controller", "--controller-manager", "/controller_manager"],
|
||||
)
|
||||
|
||||
return LaunchDescription([
|
||||
Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
name='rviz_ocs2',
|
||||
output='screen',
|
||||
arguments=["-d", rviz_config_file]
|
||||
),
|
||||
Node(
|
||||
package='ros_gz_bridge',
|
||||
executable='parameter_bridge',
|
||||
arguments=['/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock'],
|
||||
output='screen'
|
||||
),
|
||||
IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
[PathJoinSubstitution([FindPackageShare('ros_gz_sim'),
|
||||
'launch',
|
||||
'gz_sim.launch.py'])]),
|
||||
launch_arguments=[('gz_args', [' -r -v 4 empty.sdf'])]),
|
||||
robot_state_publisher,
|
||||
gz_spawn_entity,
|
||||
leg_pd_controller,
|
||||
RegisterEventHandler(
|
||||
event_handler=OnProcessExit(
|
||||
target_action=leg_pd_controller,
|
||||
on_exit=[imu_sensor_broadcaster, joint_state_publisher, unitree_guide_controller],
|
||||
)
|
||||
),
|
||||
])
|
|
@ -0,0 +1,93 @@
|
|||
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 = "x30_description"
|
||||
|
||||
|
||||
def process_xacro():
|
||||
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)
|
||||
return robot_description_config.toxml()
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
rviz_config_file = os.path.join(get_package_share_directory(package_description), "config", "visualize_urdf.rviz")
|
||||
|
||||
robot_description = process_xacro()
|
||||
|
||||
robot_controllers = PathJoinSubstitution(
|
||||
[
|
||||
FindPackageShare(package_description),
|
||||
"config",
|
||||
"robot_control.yaml",
|
||||
]
|
||||
)
|
||||
|
||||
controller_manager = Node(
|
||||
package="controller_manager",
|
||||
executable="ros2_control_node",
|
||||
parameters=[robot_controllers],
|
||||
output="both",
|
||||
)
|
||||
|
||||
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
|
||||
}
|
||||
],
|
||||
)
|
||||
|
||||
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 LaunchDescription([
|
||||
Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
name='rviz_ocs2',
|
||||
output='screen',
|
||||
arguments=["-d", rviz_config_file]
|
||||
),
|
||||
robot_state_publisher,
|
||||
controller_manager,
|
||||
joint_state_publisher,
|
||||
RegisterEventHandler(
|
||||
event_handler=OnProcessExit(
|
||||
target_action=joint_state_publisher,
|
||||
on_exit=[imu_sensor_broadcaster, unitree_guide_controller],
|
||||
)
|
||||
),
|
||||
])
|
|
@ -0,0 +1,49 @@
|
|||
import os
|
||||
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
|
||||
from launch import LaunchDescription
|
||||
from launch_ros.actions import Node
|
||||
|
||||
import xacro
|
||||
|
||||
package_description = "x30_description"
|
||||
|
||||
def process_xacro():
|
||||
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)
|
||||
return robot_description_config.toxml()
|
||||
def generate_launch_description():
|
||||
|
||||
rviz_config_file = os.path.join(get_package_share_directory(package_description), "config", "visualize_urdf.rviz")
|
||||
robot_description = process_xacro()
|
||||
|
||||
return LaunchDescription([
|
||||
Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
name='rviz_ocs2',
|
||||
output='screen',
|
||||
arguments=["-d", rviz_config_file]
|
||||
),
|
||||
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',
|
||||
)
|
||||
])
|
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
|
@ -0,0 +1,18 @@
|
|||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>x30_description</name>
|
||||
<version>0.0.0</version>
|
||||
<description>The x30_description package</description>
|
||||
|
||||
<maintainer email="1973671061@qq.com">ZhenyuXu</maintainer>
|
||||
<license>MIT</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,481 @@
|
|||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<robot name="X30">
|
||||
<!-- <link name="base_link">
|
||||
<inertial>
|
||||
<origin xyz="0.0 0.0 0.0"/>
|
||||
<mass value="1e-12" />
|
||||
<inertia ixx="1e-12" ixy="0" ixz="0" iyy="1e-12" iyz="0" izz="1e-12" />
|
||||
</inertial>
|
||||
</link> -->
|
||||
|
||||
<link name="TORSO">
|
||||
<inertial>
|
||||
<origin xyz="-0.0029257 7.5034e-06 0.020095" rpy="0 0 0" />
|
||||
<mass value="30.7" />
|
||||
<inertia ixx="0.364306" ixy="0.00018421" ixz="0.00027469" iyy="0.597627" iyz="0.00026784" izz="0.757267" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="../meshes/torso.dae" />
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<box size="0.44 0.26 0.15"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<!-- <joint name="base_joint" type="fixed">
|
||||
<parent link="base_link" />
|
||||
<child link="torso" />
|
||||
</joint> -->
|
||||
|
||||
<link name="FL_HIP">
|
||||
<inertial>
|
||||
<origin xyz="-0.0018591 -0.011377 0.00027039" rpy="0 0 0" />
|
||||
<mass value="1.43" />
|
||||
<inertia ixx="0.0014068" ixy="-1.8545e-05" ixz="2.7664e-06" iyy="0.0026782" iyz="2.1221e-06" izz="0.0015918" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="../meshes/hip.dae" />
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name="FL_HipX_joint" type="revolute">
|
||||
<origin xyz="0.291 0.08 0" rpy="0 0 0" />
|
||||
<parent link="TORSO" />
|
||||
<child link="FL_HIP" />
|
||||
<axis xyz="-1 0 0" />
|
||||
<dynamics damping="0.01" friction="0.03"/>
|
||||
<limit lower="-0.323" upper="0.585" effort="84" velocity="17.5" />
|
||||
</joint>
|
||||
|
||||
<link name="FL_THIGH">
|
||||
<inertial>
|
||||
<origin xyz="-0.0087581 -0.023554 -0.055162" rpy="0 0 0" />
|
||||
<mass value="4.0809" />
|
||||
<inertia ixx="0.012604" ixy="0.00020291" ixz="-0.00030875" iyy="0.0164" iyz="0.00036593" izz="0.0061084" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="../meshes/l_thigh.dae" />
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.02 0 -0.13" />
|
||||
<geometry>
|
||||
<cylinder length="0.25" radius="0.04"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="FL_HipY_joint" type="revolute">
|
||||
<origin xyz="0 0.11675 0" rpy="0 0 0" />
|
||||
<parent link="FL_HIP" />
|
||||
<child link="FL_THIGH" />
|
||||
<axis xyz="0 -1 0" />
|
||||
<dynamics damping="0.01" friction="0.03"/>
|
||||
<limit lower="-2.967" upper="0.262" effort="84" velocity="17.5" />
|
||||
</joint>
|
||||
|
||||
<link name="FL_SHANK">
|
||||
<inertial>
|
||||
<origin xyz="0.014851 2.0685e-05 -0.12283" rpy="0 0 0" />
|
||||
<mass value="0.71386" />
|
||||
<inertia ixx="0.0093039" ixy="1.7693e-07" ixz="0.00034843" iyy="0.0096272" iyz="-3.7717e-06" izz="0.00041542" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="../meshes/shank.dae" />
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0. -0.40 0." xyz="0.02 0 -0.046" />
|
||||
<geometry>
|
||||
<cylinder length="0.1" radius="0.025"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin rpy="0. 0 0." xyz="0.045 0 -0.155" />
|
||||
<geometry>
|
||||
<cylinder length="0.12" radius="0.025"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin rpy="0. 0.45 0." xyz="0.025 0 -0.246" />
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.022"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="FL_Knee_joint" type="revolute">
|
||||
<origin xyz="0 0 -0.30" rpy="0 0 0" />
|
||||
<parent link="FL_THIGH" />
|
||||
<child link="FL_SHANK" />
|
||||
<axis xyz="0 -1 0" />
|
||||
<dynamics damping="0.01" friction="0.03"/>
|
||||
<limit lower="0.349" upper="2.531" effort="180" velocity="16.1" />
|
||||
</joint>
|
||||
|
||||
<link name="FL_FOOT">
|
||||
<inertial>
|
||||
<mass value="0.06" />
|
||||
<inertia ixx="1e-12" ixy="0" ixz="0" iyy="1e-12" iyz="0" izz="1e-12" />
|
||||
</inertial>
|
||||
<collision>
|
||||
<geometry>
|
||||
<sphere radius="0.03"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="FL_Ankle" type="fixed" dont_collapse="true">
|
||||
<origin xyz="0 0 -0.31"/>
|
||||
<parent link="FL_SHANK" />
|
||||
<child link="FL_FOOT" />
|
||||
</joint>
|
||||
|
||||
<link name="FR_HIP">
|
||||
<inertial>
|
||||
<origin xyz="-0.0018591 0.011377 -2.7675e-05" rpy="3.14159 0 0" />
|
||||
<mass value="1.43" />
|
||||
<inertia ixx="0.0014068" ixy="1.8545e-05" ixz="-4.1487e-06" iyy="0.0026782" iyz="7.0795e-06" izz="0.0015918" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="../meshes/hip.dae" />
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name="FR_HipX_joint" type="revolute">
|
||||
<origin xyz="0.291 -0.08 0" rpy="0 0 0" />
|
||||
<parent link="TORSO" />
|
||||
<child link="FR_HIP" />
|
||||
<axis xyz="-1 0 0" />
|
||||
<dynamics damping="0.01" friction="0.03"/>
|
||||
<limit lower="-0.585" upper="0.323" effort="84" velocity="17.5" />
|
||||
</joint>
|
||||
|
||||
<link name="FR_THIGH">
|
||||
<inertial>
|
||||
<origin xyz="-0.0087433 0.023551 -0.055154" rpy="0 0 0" />
|
||||
<mass value="4.0809" />
|
||||
<inertia ixx="0.012604" ixy="-0.00020374" ixz="-0.0003086" iyy="0.0164" iyz="-0.00036585" izz="0.0061086" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="../meshes/r_thigh.dae" />
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.02 0 -0.13" />
|
||||
<geometry>
|
||||
<cylinder length="0.25" radius="0.04"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="FR_HipY_joint" type="revolute">
|
||||
<origin xyz="0 -0.11675 0" rpy="0 0 0" />
|
||||
<parent link="FR_HIP" />
|
||||
<child link="FR_THIGH" />
|
||||
<axis xyz="0 -1 0" />
|
||||
<dynamics damping="0.01" friction="0.03"/>
|
||||
<limit lower="-2.967" upper="0.262" effort="84" velocity="17.5" />
|
||||
</joint>
|
||||
|
||||
<link name="FR_SHANK">
|
||||
<inertial>
|
||||
<origin xyz="0.014851 2.0687e-05 -0.12283" rpy="0 0 0" />
|
||||
<mass value="0.71386" />
|
||||
<inertia ixx="0.0093039" ixy="1.7692e-07" ixz="0.00034843" iyy="0.0096272" iyz="-3.7714e-06" izz="0.00041542" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="../meshes/shank.dae" />
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0. -0.40 0." xyz="0.02 0 -0.046" />
|
||||
<geometry>
|
||||
<cylinder length="0.1" radius="0.025"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin rpy="0. 0 0." xyz="0.045 0 -0.155" />
|
||||
<geometry>
|
||||
<cylinder length="0.12" radius="0.025"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin rpy="0. 0.45 0." xyz="0.025 0 -0.246" />
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.022"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="FR_Knee_joint" type="revolute">
|
||||
<origin xyz="0 0 -0.30" rpy="0 0 0" />
|
||||
<parent link="FR_THIGH" />
|
||||
<child link="FR_SHANK" />
|
||||
<axis xyz="0 -1 0" />
|
||||
<dynamics damping="0.01" friction="0.03"/>
|
||||
<limit lower="0.349" upper="2.531" effort="180" velocity="16.1" />
|
||||
</joint>
|
||||
|
||||
<link name="FR_FOOT">
|
||||
<inertial>
|
||||
<mass value="0.06" />
|
||||
<inertia ixx="1e-12" ixy="0" ixz="0" iyy="1e-12" iyz="0" izz="1e-12" />
|
||||
</inertial>
|
||||
<collision>
|
||||
<geometry>
|
||||
<sphere radius="0.03"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="FR_Ankle" type="fixed" dont_collapse="true">
|
||||
<origin xyz="0 0 -0.31"/>
|
||||
<parent link="FR_SHANK" />
|
||||
<child link="FR_FOOT" />
|
||||
</joint>
|
||||
|
||||
|
||||
<link name="HL_HIP">
|
||||
<inertial>
|
||||
<origin xyz="0.0018591 -0.011377 -2.7675e-05" rpy="0 3.14159 0" />
|
||||
<mass value="1.43" />
|
||||
<inertia ixx="0.0014068" ixy="1.8545e-05" ixz="4.1487e-06" iyy="0.0026782" iyz="-7.0795e-06" izz="0.0015918" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="../meshes/hip.dae" />
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name="HL_HipX_joint" type="revolute">
|
||||
<origin xyz="-0.291 0.08 0" rpy="0 0 0" />
|
||||
<parent link="TORSO" />
|
||||
<child link="HL_HIP" />
|
||||
<axis xyz="-1 0 0" />
|
||||
<dynamics damping="0.01" friction="0.03"/>
|
||||
<limit lower="-0.323" upper="0.585" effort="84" velocity="17.5" />
|
||||
</joint>
|
||||
|
||||
<link name="HL_THIGH">
|
||||
<inertial>
|
||||
<origin xyz="-0.0087581 -0.023554 -0.055162" rpy="0 0 0" />
|
||||
<mass value="4.0809" />
|
||||
<inertia ixx="0.012604" ixy="0.00020291" ixz="-0.00030875" iyy="0.0164" iyz="0.00036593" izz="0.0061084" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="../meshes/l_thigh.dae" />
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.02 0 -0.13" />
|
||||
<geometry>
|
||||
<cylinder length="0.25" radius="0.04"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="HL_HipY_joint" type="revolute">
|
||||
<origin xyz="0 0.11675 0" rpy="0 0 0" />
|
||||
<parent link="HL_HIP" />
|
||||
<child link="HL_THIGH" />
|
||||
<axis xyz="0 -1 0" />
|
||||
<dynamics damping="0.01" friction="0.03"/>
|
||||
<limit lower="-2.967" upper="0.262" effort="84" velocity="17.5" />
|
||||
</joint>
|
||||
|
||||
<link name="HL_SHANK">
|
||||
<inertial>
|
||||
<origin xyz="0.014851 2.0679e-05 -0.12283" rpy="0 0 0" />
|
||||
<mass value="0.71386" />
|
||||
<inertia ixx="0.0093039" ixy="1.7692e-07" ixz="0.00034843" iyy="0.0096272" iyz="-3.7714e-06" izz="0.00041542" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="../meshes/shank.dae" />
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0. -0.40 0." xyz="0.02 0 -0.046" />
|
||||
<geometry>
|
||||
<cylinder length="0.1" radius="0.025"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin rpy="0. 0 0." xyz="0.045 0 -0.155" />
|
||||
<geometry>
|
||||
<cylinder length="0.12" radius="0.025"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin rpy="0. 0.45 0." xyz="0.025 0 -0.246" />
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.022"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="HL_Knee_joint" type="revolute">
|
||||
<origin xyz="0 0 -0.30" rpy="0 0 0" />
|
||||
<parent link="HL_THIGH" />
|
||||
<child link="HL_SHANK" />
|
||||
<axis xyz="0 -1 0" />
|
||||
<dynamics damping="0.01" friction="0.03"/>
|
||||
<limit lower="0.349" upper="2.531" effort="180" velocity="16.1" />
|
||||
</joint>
|
||||
|
||||
<link name="HL_FOOT">
|
||||
<inertial>
|
||||
<mass value="0.06" />
|
||||
<inertia ixx="1e-12" ixy="0" ixz="0" iyy="1e-12" iyz="0" izz="1e-12" />
|
||||
</inertial>
|
||||
<collision>
|
||||
<geometry>
|
||||
<sphere radius="0.03"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="HL_Ankle" type="fixed" dont_collapse="true">
|
||||
<origin xyz="0 0 -0.31"/>
|
||||
<parent link="HL_SHANK" />
|
||||
<child link="HL_FOOT" />
|
||||
</joint>
|
||||
|
||||
<link name="HR_HIP">
|
||||
<inertial>
|
||||
<origin xyz="0.0018591 0.011377 0.00027039" rpy="3.14159 3.14159 0" />
|
||||
<mass value="1.43" />
|
||||
<inertia ixx="0.0014068" ixy="-1.8545e-05" ixz="-2.7664e-06" iyy="0.0026782" iyz="-2.1221e-06" izz="0.0015918" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="../meshes/hip.dae" />
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name="HR_HipX_joint" type="revolute">
|
||||
<origin xyz="-0.291 -0.08 0" rpy="0 0 0" />
|
||||
<parent link="TORSO" />
|
||||
<child link="HR_HIP" />
|
||||
<axis xyz="-1 0 0" />
|
||||
<dynamics damping="0.01" friction="0.03"/>
|
||||
<limit lower="-0.585" upper="0.323" effort="84" velocity="17.5" />
|
||||
</joint>
|
||||
|
||||
<link name="HR_THIGH">
|
||||
<inertial>
|
||||
<origin xyz="-0.0087433 0.023551 -0.055154" rpy="0 0 0" />
|
||||
<mass value="4.0809" />
|
||||
<inertia ixx="0.012604" ixy="-0.00020374" ixz="-0.0003086" iyy="0.0164" iyz="-0.00036585" izz="0.0061086" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="../meshes/r_thigh.dae" />
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.02 0 -0.13" />
|
||||
<geometry>
|
||||
<cylinder length="0.25" radius="0.04"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="HR_HipY_joint" type="revolute">
|
||||
<origin xyz="0 -0.11675 0" rpy="0 0 0" />
|
||||
<parent link="HR_HIP" />
|
||||
<child link="HR_THIGH" />
|
||||
<axis xyz="0 -1 0" />
|
||||
<dynamics damping="0.01" friction="0.03"/>
|
||||
<limit lower="-2.967" upper="0.262" effort="84" velocity="17.5" />
|
||||
</joint>
|
||||
|
||||
<link name="HR_SHANK">
|
||||
<inertial>
|
||||
<origin xyz="0.014851 2.0679e-05 -0.12283" rpy="0 0 0" />
|
||||
<mass value="0.71386" />
|
||||
<inertia ixx="0.0093039" ixy="1.7692e-07" ixz="0.00034843" iyy="0.0096272" iyz="-3.7714e-06" izz="0.00041542" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="../meshes/shank.dae" />
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0. -0.40 0." xyz="0.02 0 -0.046" />
|
||||
<geometry>
|
||||
<cylinder length="0.1" radius="0.025"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin rpy="0. 0 0." xyz="0.045 0 -0.155" />
|
||||
<geometry>
|
||||
<cylinder length="0.12" radius="0.025"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin rpy="0. 0.45 0." xyz="0.025 0 -0.246" />
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.022"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="HR_Knee_joint" type="revolute">
|
||||
<origin xyz="0 0 -0.30" rpy="0 0 0" />
|
||||
<parent link="HR_THIGH" />
|
||||
<child link="HR_SHANK" />
|
||||
<axis xyz="0 -1 0" />
|
||||
<dynamics damping="0.01" friction="0.03"/>
|
||||
<limit lower="0.349" upper="2.531" effort="180" velocity="16.1" />
|
||||
</joint>
|
||||
|
||||
<link name="HR_FOOT">
|
||||
<inertial>
|
||||
<mass value="0.06" />
|
||||
<inertia ixx="1e-12" ixy="0" ixz="0" iyy="1e-12" iyz="0" izz="1e-12" />
|
||||
</inertial>
|
||||
<collision>
|
||||
<geometry>
|
||||
<sphere radius="0.03"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="HR_Ankle" type="fixed" dont_collapse="true">
|
||||
<origin xyz="0 0 -0.31"/>
|
||||
<parent link="HR_SHANK" />
|
||||
<child link="HR_FOOT" />
|
||||
</joint>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,474 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:include filename="$(find x30_description)/xacro/imu_link.xacro"/>
|
||||
|
||||
<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="TORSO"/>
|
||||
</joint>
|
||||
|
||||
<link name="TORSO">
|
||||
<inertial>
|
||||
<origin xyz="-0.0029257 7.5034e-06 0.020095" rpy="0 0 0"/>
|
||||
<mass value="30.7"/>
|
||||
<inertia ixx="0.364306" ixy="0.00018421" ixz="0.00027469" iyy="0.597627" iyz="0.00026784" izz="0.757267"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find x30_description)/meshes/torso.dae"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.44 0.26 0.15"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="FL_HIP">
|
||||
<inertial>
|
||||
<origin xyz="-0.0018591 -0.011377 0.00027039" rpy="0 0 0"/>
|
||||
<mass value="1.43"/>
|
||||
<inertia ixx="0.0014068" ixy="-1.8545e-05" ixz="2.7664e-06" iyy="0.0026782" iyz="2.1221e-06" izz="0.0015918"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find x30_description)/meshes/hip.dae"/>
|
||||
</geometry>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name="FL_HipX" type="revolute">
|
||||
<origin xyz="0.291 0.08 0" rpy="0 0 0"/>
|
||||
<parent link="TORSO"/>
|
||||
<child link="FL_HIP"/>
|
||||
<axis xyz="-1 0 0"/>
|
||||
<limit lower="-0.323" upper="0.585" effort="84" velocity="17.5"/>
|
||||
</joint>
|
||||
|
||||
<link name="FL_THIGH">
|
||||
<inertial>
|
||||
<origin xyz="-0.0087581 -0.023554 -0.055162" rpy="0 0 0"/>
|
||||
<mass value="4.0809"/>
|
||||
<inertia ixx="0.012604" ixy="0.00020291" ixz="-0.00030875" iyy="0.0164" iyz="0.00036593" izz="0.0061084"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find x30_description)/meshes/l_thigh.dae"/>
|
||||
</geometry>
|
||||
<material name="light-grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.02 0 -0.13"/>
|
||||
<geometry>
|
||||
<cylinder length="0.25" radius="0.04"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="FL_HipY" type="revolute">
|
||||
<origin xyz="0 0.11675 0" rpy="0 0 0"/>
|
||||
<parent link="FL_HIP"/>
|
||||
<child link="FL_THIGH"/>
|
||||
<axis xyz="0 -1 0"/>
|
||||
<limit lower="-2.967" upper="0.262" effort="84" velocity="17.5"/>
|
||||
</joint>
|
||||
|
||||
<link name="FL_SHANK">
|
||||
<inertial>
|
||||
<origin xyz="0.014851 2.0685e-05 -0.12283" rpy="0 0 0"/>
|
||||
<mass value="0.71386"/>
|
||||
<inertia ixx="0.0093039" ixy="1.7693e-07" ixz="0.00034843" iyy="0.0096272" iyz="-3.7717e-06" izz="0.00041542"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find x30_description)/meshes/shank.dae"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0. -0.40 0." xyz="0.02 0 -0.046"/>
|
||||
<geometry>
|
||||
<cylinder length="0.1" radius="0.025"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin rpy="0. 0 0." xyz="0.045 0 -0.155"/>
|
||||
<geometry>
|
||||
<cylinder length="0.12" radius="0.025"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin rpy="0. 0.45 0." xyz="0.025 0 -0.246"/>
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.022"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="FL_Knee" type="revolute">
|
||||
<origin xyz="0 0 -0.30" rpy="0 0 0" />
|
||||
<parent link="FL_THIGH" />
|
||||
<child link="FL_SHANK" />
|
||||
<axis xyz="0 -1 0" />
|
||||
<limit lower="0.349" upper="2.531" effort="180" velocity="16.1" />
|
||||
</joint>
|
||||
|
||||
<link name="FL_FOOT">
|
||||
<inertial>
|
||||
<mass value="0.06" />
|
||||
<inertia ixx="1e-12" ixy="0" ixz="0" iyy="1e-12" iyz="0" izz="1e-12" />
|
||||
</inertial>
|
||||
<collision>
|
||||
<geometry>
|
||||
<sphere radius="0.03"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="FL_Ankle" type="fixed" dont_collapse="true">
|
||||
<origin xyz="0 0 -0.31"/>
|
||||
<parent link="FL_SHANK" />
|
||||
<child link="FL_FOOT" />
|
||||
</joint>
|
||||
|
||||
<link name="FR_HIP">
|
||||
<inertial>
|
||||
<origin xyz="-0.0018591 0.011377 -2.7675e-05" rpy="3.14159 0 0" />
|
||||
<mass value="1.43" />
|
||||
<inertia ixx="0.0014068" ixy="1.8545e-05" ixz="-4.1487e-06" iyy="0.0026782" iyz="7.0795e-06" izz="0.0015918" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find x30_description)/meshes/hip.dae"/>
|
||||
</geometry>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name="FR_HipX" type="revolute">
|
||||
<origin xyz="0.291 -0.08 0" rpy="0 0 0" />
|
||||
<parent link="TORSO" />
|
||||
<child link="FR_HIP" />
|
||||
<axis xyz="-1 0 0" />
|
||||
<limit lower="-0.585" upper="0.323" effort="84" velocity="17.5" />
|
||||
</joint>
|
||||
|
||||
<link name="FR_THIGH">
|
||||
<inertial>
|
||||
<origin xyz="-0.0087433 0.023551 -0.055154" rpy="0 0 0" />
|
||||
<mass value="4.0809" />
|
||||
<inertia ixx="0.012604" ixy="-0.00020374" ixz="-0.0003086" iyy="0.0164" iyz="-0.00036585" izz="0.0061086" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find x30_description)/meshes/r_thigh.dae"/>
|
||||
</geometry>
|
||||
<material name="light-grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.02 0 -0.13" />
|
||||
<geometry>
|
||||
<cylinder length="0.25" radius="0.04"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="FR_HipY" type="revolute">
|
||||
<origin xyz="0 -0.11675 0" rpy="0 0 0" />
|
||||
<parent link="FR_HIP" />
|
||||
<child link="FR_THIGH" />
|
||||
<axis xyz="0 -1 0" />
|
||||
<limit lower="-2.967" upper="0.262" effort="84" velocity="17.5" />
|
||||
</joint>
|
||||
|
||||
<link name="FR_SHANK">
|
||||
<inertial>
|
||||
<origin xyz="0.014851 2.0687e-05 -0.12283" rpy="0 0 0" />
|
||||
<mass value="0.71386" />
|
||||
<inertia ixx="0.0093039" ixy="1.7692e-07" ixz="0.00034843" iyy="0.0096272" iyz="-3.7714e-06" izz="0.00041542" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find x30_description)/meshes/shank.dae"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0. -0.40 0." xyz="0.02 0 -0.046" />
|
||||
<geometry>
|
||||
<cylinder length="0.1" radius="0.025"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin rpy="0. 0 0." xyz="0.045 0 -0.155" />
|
||||
<geometry>
|
||||
<cylinder length="0.12" radius="0.025"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin rpy="0. 0.45 0." xyz="0.025 0 -0.246" />
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.022"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="FR_Knee" type="revolute">
|
||||
<origin xyz="0 0 -0.30" rpy="0 0 0" />
|
||||
<parent link="FR_THIGH" />
|
||||
<child link="FR_SHANK" />
|
||||
<axis xyz="0 -1 0" />
|
||||
<limit lower="0.349" upper="2.531" effort="180" velocity="16.1" />
|
||||
</joint>
|
||||
|
||||
<link name="FR_FOOT">
|
||||
<inertial>
|
||||
<mass value="0.06" />
|
||||
<inertia ixx="1e-12" ixy="0" ixz="0" iyy="1e-12" iyz="0" izz="1e-12" />
|
||||
</inertial>
|
||||
<collision>
|
||||
<geometry>
|
||||
<sphere radius="0.03"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="FR_Ankle" type="fixed" dont_collapse="true">
|
||||
<origin xyz="0 0 -0.31"/>
|
||||
<parent link="FR_SHANK" />
|
||||
<child link="FR_FOOT" />
|
||||
</joint>
|
||||
|
||||
<link name="HL_HIP">
|
||||
<inertial>
|
||||
<origin xyz="0.0018591 -0.011377 -2.7675e-05" rpy="0 3.14159 0" />
|
||||
<mass value="1.43" />
|
||||
<inertia ixx="0.0014068" ixy="1.8545e-05" ixz="4.1487e-06" iyy="0.0026782" iyz="-7.0795e-06" izz="0.0015918" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find x30_description)/meshes/hip.dae"/>
|
||||
</geometry>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name="HL_HipX" type="revolute">
|
||||
<origin xyz="-0.291 0.08 0" rpy="0 0 0" />
|
||||
<parent link="TORSO" />
|
||||
<child link="HL_HIP" />
|
||||
<axis xyz="-1 0 0" />
|
||||
<limit lower="-0.323" upper="0.585" effort="84" velocity="17.5" />
|
||||
</joint>
|
||||
|
||||
<link name="HL_THIGH">
|
||||
<inertial>
|
||||
<origin xyz="-0.0087581 -0.023554 -0.055162" rpy="0 0 0" />
|
||||
<mass value="4.0809" />
|
||||
<inertia ixx="0.012604" ixy="0.00020291" ixz="-0.00030875" iyy="0.0164" iyz="0.00036593" izz="0.0061084" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find x30_description)/meshes/l_thigh.dae"/>
|
||||
</geometry>
|
||||
<material name="light-grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.02 0 -0.13" />
|
||||
<geometry>
|
||||
<cylinder length="0.25" radius="0.04"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="HL_HipY" type="revolute">
|
||||
<origin xyz="0 0.11675 0" rpy="0 0 0" />
|
||||
<parent link="HL_HIP" />
|
||||
<child link="HL_THIGH" />
|
||||
<axis xyz="0 -1 0" />
|
||||
<limit lower="-2.967" upper="0.262" effort="84" velocity="17.5" />
|
||||
</joint>
|
||||
|
||||
<link name="HL_SHANK">
|
||||
<inertial>
|
||||
<origin xyz="0.014851 2.0679e-05 -0.12283" rpy="0 0 0" />
|
||||
<mass value="0.71386" />
|
||||
<inertia ixx="0.0093039" ixy="1.7692e-07" ixz="0.00034843" iyy="0.0096272" iyz="-3.7714e-06" izz="0.00041542" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find x30_description)/meshes/shank.dae"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0. -0.40 0." xyz="0.02 0 -0.046" />
|
||||
<geometry>
|
||||
<cylinder length="0.1" radius="0.025"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin rpy="0. 0 0." xyz="0.045 0 -0.155" />
|
||||
<geometry>
|
||||
<cylinder length="0.12" radius="0.025"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin rpy="0. 0.45 0." xyz="0.025 0 -0.246" />
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.022"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="HL_Knee" type="revolute">
|
||||
<origin xyz="0 0 -0.30" rpy="0 0 0" />
|
||||
<parent link="HL_THIGH" />
|
||||
<child link="HL_SHANK" />
|
||||
<axis xyz="0 -1 0" />
|
||||
<limit lower="0.349" upper="2.531" effort="180" velocity="16.1" />
|
||||
</joint>
|
||||
|
||||
<link name="HL_FOOT">
|
||||
<inertial>
|
||||
<mass value="0.06" />
|
||||
<inertia ixx="1e-12" ixy="0" ixz="0" iyy="1e-12" iyz="0" izz="1e-12" />
|
||||
</inertial>
|
||||
<collision>
|
||||
<geometry>
|
||||
<sphere radius="0.03"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="HL_Ankle" type="fixed" dont_collapse="true">
|
||||
<origin xyz="0 0 -0.31"/>
|
||||
<parent link="HL_SHANK" />
|
||||
<child link="HL_FOOT" />
|
||||
</joint>
|
||||
|
||||
<link name="HR_HIP">
|
||||
<inertial>
|
||||
<origin xyz="0.0018591 0.011377 0.00027039" rpy="3.14159 3.14159 0" />
|
||||
<mass value="1.43" />
|
||||
<inertia ixx="0.0014068" ixy="-1.8545e-05" ixz="-2.7664e-06" iyy="0.0026782" iyz="-2.1221e-06" izz="0.0015918" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find x30_description)/meshes/hip.dae"/>
|
||||
</geometry>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name="HR_HipX" type="revolute">
|
||||
<origin xyz="-0.291 -0.08 0" rpy="0 0 0" />
|
||||
<parent link="TORSO" />
|
||||
<child link="HR_HIP" />
|
||||
<axis xyz="-1 0 0" />
|
||||
<limit lower="-0.585" upper="0.323" effort="84" velocity="17.5" />
|
||||
</joint>
|
||||
|
||||
<link name="HR_THIGH">
|
||||
<inertial>
|
||||
<origin xyz="-0.0087433 0.023551 -0.055154" rpy="0 0 0" />
|
||||
<mass value="4.0809" />
|
||||
<inertia ixx="0.012604" ixy="-0.00020374" ixz="-0.0003086" iyy="0.0164" iyz="-0.00036585" izz="0.0061086" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find x30_description)/meshes/r_thigh.dae"/>
|
||||
</geometry>
|
||||
<material name="light-grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.02 0 -0.13" />
|
||||
<geometry>
|
||||
<cylinder length="0.25" radius="0.04"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="HR_HipY" type="revolute">
|
||||
<origin xyz="0 -0.11675 0" rpy="0 0 0" />
|
||||
<parent link="HR_HIP" />
|
||||
<child link="HR_THIGH" />
|
||||
<axis xyz="0 -1 0" />
|
||||
<limit lower="-2.967" upper="0.262" effort="84" velocity="17.5" />
|
||||
</joint>
|
||||
|
||||
<link name="HR_SHANK">
|
||||
<inertial>
|
||||
<origin xyz="0.014851 2.0679e-05 -0.12283" rpy="0 0 0" />
|
||||
<mass value="0.71386" />
|
||||
<inertia ixx="0.0093039" ixy="1.7692e-07" ixz="0.00034843" iyy="0.0096272" iyz="-3.7714e-06" izz="0.00041542" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find x30_description)/meshes/shank.dae"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0. -0.40 0." xyz="0.02 0 -0.046" />
|
||||
<geometry>
|
||||
<cylinder length="0.1" radius="0.025"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin rpy="0. 0 0." xyz="0.045 0 -0.155" />
|
||||
<geometry>
|
||||
<cylinder length="0.12" radius="0.025"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin rpy="0. 0.45 0." xyz="0.025 0 -0.246" />
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.022"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="HR_Knee" type="revolute">
|
||||
<origin xyz="0 0 -0.30" rpy="0 0 0" />
|
||||
<parent link="HR_THIGH" />
|
||||
<child link="HR_SHANK" />
|
||||
<axis xyz="0 -1 0" />
|
||||
<limit lower="0.349" upper="2.531" effort="180" velocity="16.1" />
|
||||
</joint>
|
||||
|
||||
<link name="HR_FOOT">
|
||||
<inertial>
|
||||
<mass value="0.06" />
|
||||
<inertia ixx="1e-12" ixy="0" ixz="0" iyy="1e-12" iyz="0" izz="1e-12" />
|
||||
</inertial>
|
||||
<collision>
|
||||
<geometry>
|
||||
<sphere radius="0.03"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="HR_Ankle" type="fixed" dont_collapse="true">
|
||||
<origin xyz="0 0 -0.31"/>
|
||||
<parent link="HR_SHANK" />
|
||||
<child link="HR_FOOT" />
|
||||
</joint>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,195 @@
|
|||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<ros2_control name="GazeboSystem" type="system">
|
||||
<hardware>
|
||||
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
|
||||
</hardware>
|
||||
|
||||
<joint name="FR_HipX">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="FR_HipY">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="FR_Knee">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="FL_HipX">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="FL_HipY">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="FL_Knee">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="HR_HipX">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="HR_HipY">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="HR_Knee">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="HL_HipX">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="HL_HipY">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="HL_Knee">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<sensor name="imu_sensor">
|
||||
<state_interface name="orientation.x"/>
|
||||
<state_interface name="orientation.y"/>
|
||||
<state_interface name="orientation.z"/>
|
||||
<state_interface name="orientation.w"/>
|
||||
<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>
|
||||
</ros2_control>
|
||||
|
||||
<gazebo>
|
||||
<plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
|
||||
<parameters>$(find x30_description)/config/gazebo.yaml</parameters>
|
||||
</plugin>
|
||||
<plugin filename="gz-sim-imu-system"
|
||||
name="gz::sim::systems::Imu">
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="trunk">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<visual>
|
||||
<material>
|
||||
<ambient>.05 .05 .05 1.0</ambient>
|
||||
<diffuse>.05 .05 .05 1.0</diffuse>
|
||||
<specular>.05 .05 .05 1.0</specular>
|
||||
</material>
|
||||
</visual>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="imu_link">
|
||||
<sensor name="imu_sensor" type="imu">
|
||||
<always_on>1</always_on>
|
||||
<update_rate>500</update_rate>
|
||||
<visualize>true</visualize>
|
||||
<topic>imu</topic>
|
||||
<imu>
|
||||
<angular_velocity>
|
||||
<x>
|
||||
<!-- <noise type="gaussian">-->
|
||||
<!-- <mean>0.0</mean>-->
|
||||
<!-- <stddev>2e-4</stddev>-->
|
||||
<!-- <bias_mean>0.0000075</bias_mean>-->
|
||||
<!-- <bias_stddev>0.0000008</bias_stddev>-->
|
||||
<!-- </noise>-->
|
||||
</x>
|
||||
<y>
|
||||
<!-- <noise type="gaussian">-->
|
||||
<!-- <mean>0.0</mean>-->
|
||||
<!-- <stddev>2e-4</stddev>-->
|
||||
<!-- <bias_mean>0.0000075</bias_mean>-->
|
||||
<!-- <bias_stddev>0.0000008</bias_stddev>-->
|
||||
<!-- </noise>-->
|
||||
</y>
|
||||
<z>
|
||||
<!-- <noise type="gaussian">-->
|
||||
<!-- <mean>0.0</mean>-->
|
||||
<!-- <stddev>2e-4</stddev>-->
|
||||
<!-- <bias_mean>0.0000075</bias_mean>-->
|
||||
<!-- <bias_stddev>0.0000008</bias_stddev>-->
|
||||
<!-- </noise>-->
|
||||
</z>
|
||||
</angular_velocity>
|
||||
<linear_acceleration>
|
||||
<x>
|
||||
<!-- <noise type="gaussian">-->
|
||||
<!-- <mean>0.0</mean>-->
|
||||
<!-- <stddev>1.7e-2</stddev>-->
|
||||
<!-- <bias_mean>0.1</bias_mean>-->
|
||||
<!-- <bias_stddev>0.001</bias_stddev>-->
|
||||
<!-- </noise>-->
|
||||
</x>
|
||||
<y>
|
||||
<!-- <noise type="gaussian">-->
|
||||
<!-- <mean>0.0</mean>-->
|
||||
<!-- <stddev>1.7e-2</stddev>-->
|
||||
<!-- <bias_mean>0.1</bias_mean>-->
|
||||
<!-- <bias_stddev>0.001</bias_stddev>-->
|
||||
<!-- </noise>-->
|
||||
</y>
|
||||
<z>
|
||||
<!-- <noise type="gaussian">-->
|
||||
<!-- <mean>0.0</mean>-->
|
||||
<!-- <stddev>1.7e-2</stddev>-->
|
||||
<!-- <bias_mean>0.1</bias_mean>-->
|
||||
<!-- <bias_stddev>0.001</bias_stddev>-->
|
||||
<!-- </noise>-->
|
||||
</z>
|
||||
</linear_acceleration>
|
||||
</imu>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<gazebo reference="imu_joint">
|
||||
<disableFixedJointLumping>true</disableFixedJointLumping>
|
||||
</gazebo>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,30 @@
|
|||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<parent link="TORSO"/>
|
||||
<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>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size=".001 .001 .001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,36 @@
|
|||
<?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="deep-grey">
|
||||
<color rgba="0.1 0.1 0.1 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="grey">
|
||||
<color rgba="0.2 0.2 0.2 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="light-grey">
|
||||
<color rgba="0.35 0.35 0.35 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="silver">
|
||||
<color rgba="${233/255} ${233/255} ${216/255} 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="white">
|
||||
<color rgba="1.0 1.0 1.0 1.0"/>
|
||||
</material>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,17 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot name="x30" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:include filename="$(find x30_description)/xacro/body.xacro"/>
|
||||
<xacro:include filename="$(find x30_description)/xacro/materials.xacro"/>
|
||||
<xacro:include filename="$(find x30_description)/xacro/transmission.xacro"/>
|
||||
|
||||
<xacro:arg name="GAZEBO" default="false"/>
|
||||
<xacro:if value="$(arg GAZEBO)">
|
||||
<xacro:include filename="$(find x30_description)/xacro/gazebo.xacro"/>
|
||||
</xacro:if>
|
||||
<xacro:unless value="$(arg GAZEBO)">
|
||||
<xacro:include filename="$(find x30_description)/xacro/ros2_control.xacro"/>
|
||||
</xacro:unless>
|
||||
|
||||
</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_HipX">
|
||||
<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_HipY">
|
||||
<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_Knee">
|
||||
<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_HipX">
|
||||
<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_HipY">
|
||||
<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_Knee">
|
||||
<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="HR_HipX">
|
||||
<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="HR_HipY">
|
||||
<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="HR_Knee">
|
||||
<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="HL_HipX">
|
||||
<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="HL_HipY">
|
||||
<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="HL_Knee">
|
||||
<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="HR"/>
|
||||
<state_interface name="HL"/>
|
||||
</sensor>
|
||||
|
||||
</ros2_control>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,129 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<!-- FL transmissions -->
|
||||
<transmission name="FL_HipX_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FL_HipX">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FL_HipX_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="FL_HipY_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FL_HipY">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FL_HipY_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="FL_Knee_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FL_Knee">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FL_Knee_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<!-- FR transmissions -->
|
||||
<transmission name="FR_HipX_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FR_HipX">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FR_HipX_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="FR_HipY_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FR_HipY">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FR_HipY_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="FR_Knee_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FR_Knee">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FR_Knee_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<!-- HL transmissions -->
|
||||
<transmission name="HL_HipX_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="HL_HipX">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="HL_HipX_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="HL_HipY_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="HL_HipY">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="HL_HipY_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="HL_Knee_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="HL_Knee">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="HL_Knee_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<!-- HR transmissions -->
|
||||
<transmission name="HR_HipX_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="HR_HipX">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="HR_HipX_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="HR_HipY_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="HR_HipY">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="HR_HipY_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="HR_Knee_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="HR_Knee">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="HR_Knee_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
</robot>
|
Loading…
Reference in New Issue