Add b2 urdf for ros and isaac. Add b2 mujoco.

This commit is contained in:
BDLUO 2023-12-11 22:00:05 +08:00
parent e197ae10d3
commit e7ad0b7d92
72 changed files with 836585 additions and 0 deletions

View File

@ -0,0 +1,14 @@
cmake_minimum_required(VERSION 2.8.3)
project(b2_description)
find_package(catkin REQUIRED)
catkin_package()
find_package(roslaunch)
foreach(dir config launch meshes urdf)
install(DIRECTORY ${dir}/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir})
endforeach(dir)

View File

@ -0,0 +1,45 @@
## b2_urdf
This repository contains the urdf model of b2.
## Build the library
Create a new catkin workspace:
```
# Create the directories
# Do not forget to change <...> parts
mkdir -p <directory_to_ws>/<catkin_ws_name>/src
cd <directory_to_ws>/<catkin_ws_name>/
# Initialize the catkin workspace
catkin init
```
Clone library:
```
# Navigate to the directory of src
# Do not forget to change <...> parts
cd <directory_to_ws>/<catkin_ws_name>/src
git clone git@github.com:unitreerobotics
```
Build:
```
# Build it
catkin build
# Source it
source <directory_to_ws>/<catkin_ws_name>/devel/setup.bash
```
## Run the library
```
# Show urdf model of b2 in Rviz
roslaunch b2_description display.launch
```
## support issac

View File

@ -0,0 +1,361 @@
Panels:
- Class: rviz/Displays
Help Height: 138
Name: Displays
Property Tree Widget:
Expanded: ~
Splitter Ratio: 0.8341270089149475
Tree Height: 1576
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Name: Time
SyncMode: 0
SyncSource: ""
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/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: 0.5
Class: rviz/RobotModel
Collision Enabled: false
Enabled: true
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
f_dc_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
f_oc_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fl_c_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fl_f_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fl_h_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fl_t_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fr_c_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fr_f_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fr_h_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
fr_t_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
head_Link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
imu_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
lidar_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_dc_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
r_oc_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rl_c_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rl_f_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rl_h_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rl_t_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rr_c_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rr_f_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rr_h_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rr_t_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
tail_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Name: RobotModel
Robot Description: robot_description
TF Prefix: ""
Update Interval: 0
Value: true
Visual Enabled: true
- Class: rviz/TF
Enabled: true
Filter (blacklist): ""
Filter (whitelist): ""
Frame Timeout: 15
Frames:
All Enabled: true
base_link:
Value: true
f_dc_link:
Value: true
f_oc_link:
Value: true
fl_c_link:
Value: true
fl_f_link:
Value: true
fl_h_link:
Value: true
fl_t_link:
Value: true
fr_c_link:
Value: true
fr_f_link:
Value: true
fr_h_link:
Value: true
fr_t_link:
Value: true
head_Link:
Value: true
imu_link:
Value: true
lidar_link:
Value: true
r_dc_link:
Value: true
r_oc_link:
Value: true
rl_c_link:
Value: true
rl_f_link:
Value: true
rl_h_link:
Value: true
rl_t_link:
Value: true
rr_c_link:
Value: true
rr_f_link:
Value: true
rr_h_link:
Value: true
rr_t_link:
Value: true
tail_link:
Value: true
Marker Alpha: 1
Marker Scale: 0.4000000059604645
Name: TF
Show Arrows: true
Show Axes: true
Show Names: true
Tree:
base_link:
f_dc_link:
{}
f_oc_link:
{}
fl_h_link:
fl_t_link:
fl_c_link:
fl_f_link:
{}
fr_h_link:
fr_t_link:
fr_c_link:
fr_f_link:
{}
head_Link:
{}
imu_link:
{}
lidar_link:
{}
r_dc_link:
{}
r_oc_link:
{}
rl_h_link:
rl_t_link:
rl_c_link:
rl_f_link:
{}
rr_h_link:
rr_t_link:
rr_c_link:
rr_f_link:
{}
tail_link:
{}
Update Interval: 0
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: base_link
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Theta std deviation: 0.2617993950843811
Topic: /initialpose
X std deviation: 0.5
Y std deviation: 0.5
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 1.8284358978271484
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Field of View: 0.7853981852531433
Focal Point:
X: 0.01927083730697632
Y: -0.037570029497146606
Z: -0.34493619203567505
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.555398166179657
Target Frame: <Fixed Frame>
Yaw: 0.7953987121582031
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 2086
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd00000004000000000000024000000720fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b000000b000fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000b0fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000006e000007200000018200fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000015f00000720fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000006e000007200000013200fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e1000001970000000300000f000000005efc0100000002fb0000000800540069006d0065010000000000000f00000006dc00fffffffb0000000800540069006d0065010000000000000450000000000000000000000cb40000072000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 3840
X: 3840
Y: 0

View File

@ -0,0 +1,70 @@
b2_gazebo:
# Publish all joint states -----------------------------------
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 1000
# FL Controllers ---------------------------------------
FL_hip_controller:
type: unitree_legged_control/UnitreeJointController
joint: FL_hip_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
FL_thigh_controller:
type: unitree_legged_control/UnitreeJointController
joint: FL_thigh_joint
pid: {p: 300.0, i: 0.0, d: 8.0}
FL_calf_controller:
type: unitree_legged_control/UnitreeJointController
joint: FL_calf_joint
pid: {p: 300.0, i: 0.0, d: 8.0}
# FR Controllers ---------------------------------------
FR_hip_controller:
type: unitree_legged_control/UnitreeJointController
joint: FR_hip_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
FR_thigh_controller:
type: unitree_legged_control/UnitreeJointController
joint: FR_thigh_joint
pid: {p: 300.0, i: 0.0, d: 8.0}
FR_calf_controller:
type: unitree_legged_control/UnitreeJointController
joint: FR_calf_joint
pid: {p: 300.0, i: 0.0, d: 8.0}
# RL Controllers ---------------------------------------
RL_hip_controller:
type: unitree_legged_control/UnitreeJointController
joint: RL_hip_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
RL_thigh_controller:
type: unitree_legged_control/UnitreeJointController
joint: RL_thigh_joint
pid: {p: 300.0, i: 0.0, d: 8.0}
RL_calf_controller:
type: unitree_legged_control/UnitreeJointController
joint: RL_calf_joint
pid: {p: 300.0, i: 0.0, d: 8.0}
# RR Controllers ---------------------------------------
RR_hip_controller:
type: unitree_legged_control/UnitreeJointController
joint: RR_hip_joint
pid: {p: 100.0, i: 0.0, d: 5.0}
RR_thigh_controller:
type: unitree_legged_control/UnitreeJointController
joint: RR_thigh_joint
pid: {p: 300.0, i: 0.0, d: 8.0}
RR_calf_controller:
type: unitree_legged_control/UnitreeJointController
joint: RR_calf_joint
pid: {p: 300.0, i: 0.0, d: 8.0}

View File

@ -0,0 +1,20 @@
<launch>
<arg
name="model" />
<param
name="robot_description"
textfile="$(find b2_description)/urdf/b2_description.urdf" />
<node
name="joint_state_publisher_gui"
pkg="joint_state_publisher_gui"
type="joint_state_publisher_gui" />
<node
name="robot_state_publisher"
pkg="robot_state_publisher"
type="robot_state_publisher" />
<node
name="rviz"
pkg="rviz"
type="rviz"
args="-d $(find b2_description)/config/config.rviz" />
</launch>

View File

@ -0,0 +1,20 @@
<launch>
<include
file="$(find gazebo_ros)/launch/empty_world.launch" />
<node
name="tf_footprint_base"
pkg="tf"
type="static_transform_publisher"
args="0 0 0 0 0 0 base_link base_footprint 40" />
<node
name="spawn_model"
pkg="gazebo_ros"
type="spawn_model"
args="-file $(find b2_description)/urdf/b2_description.urdf -urdf -model b2_description"
output="screen" />
<node
name="fake_joint_calibration"
pkg="rostopic"
type="rostopic"
args="pub /calibrated std_msgs/Bool true" />
</launch>

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

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

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

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

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,21 @@
<package format="2">
<name>b2_description</name>
<version>1.0.0</version>
<description>
<p>URDF Description package for b2_description</p>
<p>This package contains configuration data, 3D models and launch files
for b2_description robot</p>
</description>
<author>Unitree Robotics</author>
<maintainer email="TODO@email.com" />
<license>BSD</license>
<buildtool_depend>catkin</buildtool_depend>
<depend>roslaunch</depend>
<depend>robot_state_publisher</depend>
<depend>rviz</depend>
<depend>joint_state_publisher_gui</depend>
<depend>gazebo</depend>
<export>
<architecture_independent />
</export>
</package>

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,160 @@
<?xml version="1.0"?>
<robot name="b2_description" 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.28"/>
<xacro:property name="trunk_length" value="0.5"/>
<xacro:property name="trunk_height" value="0.15"/>
<xacro:property name="hip_radius" value="0.07"/>
<xacro:property name="hip_length" value="0.05"/>
<!-- <xacro:property name="thigh_shoulder_radius" value="0.044"/>
<xacro:property name="thigh_shoulder_length" value="0.08"/> -->
<xacro:property name="thigh_width" value="0.0455"/>
<xacro:property name="thigh_height" value="0.054"/>
<!-- <xacro:property name="calf_width" value="0.04"/>
<xacro:property name="calf_height" value="0.05"/> -->
<xacro:property name="foot_radius" value="0.04"/>
<!-- <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.11973"/>
<xacro:property name="thigh_length" value="0.32"/>
<xacro:property name="calf_length" value="0.35"/>
<!-- leg offset from trunk center value -->
<xacro:property name="leg_offset_x" value="0.3285"/>
<xacro:property name="leg_offset_y" value="0.072"/>
<!-- <xacro:property name="trunk_offset_z" value="0.0"/> -->
<xacro:property name="hip_offset" value="0.11973"/>
<!-- offset of link and rotor locations (left front) -->
<!-- <xacro:property name="hip_offset_x" value="0.3285"/>
<xacro:property name="hip_offset_y" value="0.072"/>
<xacro:property name="hip_offset_z" value="0.0"/> -->
<xacro:property name="hip_rotor_offset_x" value="0.20205"/>
<xacro:property name="hip_rotor_offset_y" value="0.072"/>
<xacro:property name="hip_rotor_offset_z" value="0.0"/>
<!-- <xacro:property name="thigh_offset_x" value="0"/>
<xacro:property name="thigh_offset_y" value="0.11973"/>
<xacro:property name="thigh_offset_z" value="0.0"/> -->
<xacro:property name="thigh_rotor_offset_x" value="0.0"/>
<xacro:property name="thigh_rotor_offset_y" value="0.00798"/>
<xacro:property name="thigh_rotor_offset_z" value="0.0"/>
<!-- <xacro:property name="calf_offset_x" value="0.0"/>
<xacro:property name="calf_offset_y" value="0.0"/>
<xacro:property name="calf_offset_z" value="-0.35"/> -->
<xacro:property name="calf_rotor_offset_x" value="0.0"/>
<xacro:property name="calf_rotor_offset_y" value="-0.05788"/>
<xacro:property name="calf_rotor_offset_z" value="0.0"/>
<!-- joint limits -->
<xacro:property name="damping" value="0"/>
<xacro:property name="friction" value="0"/>
<xacro:property name="hip_position_max" value="0.87"/>
<xacro:property name="hip_position_min" value="-0.87"/>
<xacro:property name="hip_velocity_max" value="23"/>
<xacro:property name="hip_torque_max" value="200"/>
<xacro:property name="thigh_position_max" value="4.69"/>
<xacro:property name="thigh_position_min" value="-94"/>
<xacro:property name="thigh_velocity_max" value="23"/>
<xacro:property name="thigh_torque_max" value="200"/>
<xacro:property name="calf_position_max" value="-0.43"/>
<xacro:property name="calf_position_min" value="-2.82"/>
<xacro:property name="calf_velocity_max" value="14"/>
<xacro:property name="calf_torque_max" value="320"/>
<!-- dynamics inertial value -->
<!-- trunk -->
<xacro:property name="trunk_mass" value="35.606"/>
<xacro:property name="trunk_com_x" value="0.000458"/>
<xacro:property name="trunk_com_y" value="0.005261"/>
<xacro:property name="trunk_com_z" value="0.000665"/>
<xacro:property name="trunk_ixx" value="0.27466"/>
<xacro:property name="trunk_ixy" value="-0.000622"/>
<xacro:property name="trunk_ixz" value="-0.00315"/>
<xacro:property name="trunk_iyy" value="1.0618"/>
<xacro:property name="trunk_iyz" value="-0.00139"/>
<xacro:property name="trunk_izz" value="1.1825"/>
<!-- hip (left front) -->
<xacro:property name="hip_mass" value="2.256"/>
<xacro:property name="hip_com_x" value="-0.009305"/>
<xacro:property name="hip_com_y" value="-0.010228"/>
<xacro:property name="hip_com_z" value="0.000264"/>
<xacro:property name="hip_ixx" value="0.0026431"/>
<xacro:property name="hip_ixy" value="0.00019234"/>
<xacro:property name="hip_ixz" value="-6.76E-06"/>
<xacro:property name="hip_iyy" value="0.0046728"/>
<xacro:property name="hip_iyz" value="-7.16E-06"/>
<xacro:property name="hip_izz" value="0.0034208"/>
<xacro:property name="hip_rotor_mass" value="0.2734"/>
<xacro:property name="hip_rotor_com_x" value="0.0"/>
<xacro:property name="hip_rotor_com_y" value="0.0"/>
<xacro:property name="hip_rotor_com_z" value="0.0"/>
<xacro:property name="hip_rotor_ixx" value="0.000144463"/>
<xacro:property name="hip_rotor_ixy" value="0.0"/>
<xacro:property name="hip_rotor_ixz" value="0.0"/>
<xacro:property name="hip_rotor_iyy" value="0.000144463"/>
<xacro:property name="hip_rotor_iyz" value="0.0"/>
<xacro:property name="hip_rotor_izz" value="0.000263053"/>
<!-- thigh -->
<xacro:property name="thigh_mass" value="3.591"/>
<xacro:property name="thigh_com_x" value="-0.004346"/>
<xacro:property name="thigh_com_y" value="-0.035797"/>
<xacro:property name="thigh_com_z" value="-0.044921"/>
<xacro:property name="thigh_ixx" value="0.041718"/>
<xacro:property name="thigh_ixy" value="0.00055623"/>
<xacro:property name="thigh_ixz" value="-0.0022768"/>
<xacro:property name="thigh_iyy" value="0.041071"/>
<xacro:property name="thigh_iyz" value="0.005796"/>
<xacro:property name="thigh_izz" value="0.0065677"/>
<xacro:property name="thigh_rotor_mass" value="0.2734"/>
<xacro:property name="thigh_rotor_com_x" value="0.0"/>
<xacro:property name="thigh_rotor_com_y" value="0.0"/>
<xacro:property name="thigh_rotor_com_z" value="0.0"/>
<xacro:property name="thigh_rotor_ixx" value="0.000144463"/>
<xacro:property name="thigh_rotor_ixy" value="0.0"/>
<xacro:property name="thigh_rotor_ixz" value="0.0"/>
<xacro:property name="thigh_rotor_iyy" value="0.000144463"/>
<xacro:property name="thigh_rotor_iyz" value="0.0"/>
<xacro:property name="thigh_rotor_izz" value="0.000263053"/>
<!-- calf -->
<xacro:property name="calf_mass" value="0.58094"/>
<xacro:property name="calf_com_x" value="0.012422"/>
<xacro:property name="calf_com_y" value="0.0"/>
<xacro:property name="calf_com_z" value="-0.12499"/>
<xacro:property name="calf_ixx" value="0.01143"/>
<xacro:property name="calf_ixy" value="0"/>
<xacro:property name="calf_ixz" value="0.000643"/>
<xacro:property name="calf_iyy" value="0.011534"/>
<xacro:property name="calf_iyz" value="0"/>
<xacro:property name="calf_izz" value="0.000331"/>
<xacro:property name="calf_rotor_mass" value="0.2734"/>
<xacro:property name="calf_rotor_com_x" value="0.0"/>
<xacro:property name="calf_rotor_com_y" value="0.0"/>
<xacro:property name="calf_rotor_com_z" value="0.0"/>
<xacro:property name="calf_rotor_ixx" value="0.000144463"/>
<xacro:property name="calf_rotor_ixy" value="0.0"/>
<xacro:property name="calf_rotor_ixz" value="0.0"/>
<xacro:property name="calf_rotor_iyy" value="0.000144463"/>
<xacro:property name="calf_rotor_iyz" value="0.0"/>
<xacro:property name="calf_rotor_izz" value="0.000263053"/>
<!-- foot -->
<xacro:property name="foot_mass" value="0.098183"/>
</robot>

View File

@ -0,0 +1,266 @@
<?xml version="1.0"?>
<robot>
<!-- ros_control plugin -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/b2_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>

View File

@ -0,0 +1,267 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find b2_description)/xacro/transmission.xacro"/>
<xacro:macro name="leg" params="name mirror mirror_dae front_hind front_hind_dae">
<joint name="${name}_hip_joint" type="revolute">
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == True)}">
<origin rpy="0 0 0" xyz="${leg_offset_x} ${-leg_offset_y} 0"/>
</xacro:if>
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == True)}">
<origin rpy="0 0 0" xyz="${leg_offset_x} ${leg_offset_y} 0"/>
</xacro:if>
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == False)}">
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${-leg_offset_y} 0"/>
</xacro:if>
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == False)}">
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${leg_offset_y} 0"/>
</xacro:if>
<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_position_min}" upper="${hip_position_max}"/>
</xacro:if>
<xacro:if value="${(mirror_dae == False)}">
<limit effort="${hip_torque_max}" velocity="${hip_velocity_max}" lower="${-hip_position_max}" upper="${-hip_position_min}"/>
</xacro:if>
</joint>
<joint name="${name}_hip_rotor_joint" type="fixed">
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == True)}">
<origin rpy="0 0 0" xyz="${hip_rotor_offset_x} ${-hip_rotor_offset_y} 0"/>
</xacro:if>
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == True)}">
<origin rpy="0 0 0" xyz="${hip_rotor_offset_x} ${hip_rotor_offset_y} 0"/>
</xacro:if>
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == False)}">
<origin rpy="0 0 0" xyz="${-hip_rotor_offset_x} ${-hip_rotor_offset_y} 0"/>
</xacro:if>
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == False)}">
<origin rpy="0 0 0" xyz="${-hip_rotor_offset_x} ${hip_rotor_offset_y} 0"/>
</xacro:if>
<parent link="trunk"/>
<child link="${name}_hip_rotor"/>
</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://b2_description/meshes/hip.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="${PI/2.0} 0 0" xyz="0 ${hip_offset*mirror} 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>
<link name="${name}_hip_rotor">
<visual>
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
<material name="green"/>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="${hip_rotor_com_x} ${hip_rotor_com_y} ${hip_rotor_com_z}"/>
<mass value="${hip_rotor_mass}"/>
<inertia
ixx="${hip_rotor_ixx}" ixy="${hip_rotor_ixy}" ixz="${hip_rotor_ixz}"
iyy="${hip_rotor_iyy}" iyz="${hip_rotor_iyz}"
izz="${hip_rotor_izz}"/>
</inertial>
</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_position_min}" upper="${thigh_position_max}"/>
</joint>
<joint name="${name}_thigh_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="${thigh_rotor_offset_x} ${thigh_rotor_offset_y*mirror} 0"/>
<parent link="${name}_hip"/>
<child link="${name}_thigh_rotor"/>
</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://b2_description/meshes/thigh.dae" scale="1 1 1"/>
</xacro:if>
<xacro:if value="${mirror_dae == False}">
<mesh filename="package://b2_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.025 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>
<link name="${name}_thigh_rotor">
<visual>
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
<material name="green"/>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="${thigh_rotor_com_x} ${thigh_rotor_com_y} ${thigh_rotor_com_z}"/>
<mass value="${thigh_rotor_mass}"/>
<inertia
ixx="${thigh_rotor_ixx}" ixy="${thigh_rotor_ixy}" ixz="${thigh_rotor_ixz}"
iyy="${thigh_rotor_iyy}" iyz="${thigh_rotor_iyz}"
izz="${thigh_rotor_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_position_min}" upper="${calf_position_max}"/>
</joint>
<joint name="${name}_calf_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="${calf_rotor_offset_x} ${calf_rotor_offset_y*mirror} 0"/>
<parent link="${name}_thigh"/>
<child link="${name}_calf_rotor"/>
</joint>
<link name="${name}_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://b2_description/meshes/calf.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.2 0" xyz="-0.002 0 -0.03"/>
<geometry>
<box size="0.1 0.0245 0.018"/>
</geometry>
</collision>
<collision>
<origin rpy="0 1.35 0" xyz="0.022 0 -0.1"/>
<geometry>
<box size="0.1 0.0245 0.018"/>
</geometry>
</collision>
<collision>
<origin rpy="0 1.53 0" xyz="0.036 0 -0.225"/>
<geometry>
<box size="0.15 0.0245 0.015"/>
</geometry>
</collision>
<collision>
<origin rpy="0 2 0" xyz="0.023 0 -0.31"/>
<geometry>
<box size="0.05 0.028 0.035"/>
</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>
<link name="${name}_calf_rotor">
<visual>
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
<material name="green"/>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="${calf_rotor_com_x} ${calf_rotor_com_y} ${calf_rotor_com_z}"/>
<mass value="${calf_rotor_mass}"/>
<inertia
ixx="${calf_rotor_ixx}" ixy="${calf_rotor_ixy}" ixz="${calf_rotor_ixz}"
iyy="${calf_rotor_iyy}" iyz="${calf_rotor_iyz}"
izz="${calf_rotor_izz}"/>
</inertial>
</link>
<joint name="${name}_foot_fixed" type="fixed">
<origin rpy="1.57 0 0" xyz="0 0 ${-(calf_length)}"/>
<parent link="${name}_calf"/>
<child link="${name}_foot"/>
</joint>
<link name="${name}_foot">
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<cylinder length="0.05" radius="0.032" />
</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>

View File

@ -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>

View File

@ -0,0 +1,182 @@
<?xml version="1.0"?>
<robot name="b2_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find b2_description)/xacro/const.xacro"/>
<xacro:include filename="$(find b2_description)/xacro/materials.xacro"/>
<xacro:include filename="$(find b2_description)/xacro/leg.xacro"/>
<xacro:include filename="$(find b2_description)/xacro/gazebo.xacro"/>
<!-- Rotor related joint and link is only for demonstrate location. -->
<!-- Actually, the rotor will rotate and the joint is not fixed. Reduction ratio should be considered. -->
<!-- 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://b2_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>
<!-- <collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://b1_description/meshes/trunk.dae" scale="1 1 1"/>
</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>
<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="head_joint" type="fixed">
<parent link="trunk"/>
<child link="head_Link"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<link name="head_Link">
<inertial>
<origin rpy="0 0 0" xyz="0.33989 -0.000168 0.12029"/>
<mass value="3.366" />
<inertia
ixx="0.026455"
ixy="3.15E-05"
ixz="0.00166"
iyy="0.029221"
iyz="-3.27E-05"
izz="0.010918" />
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0.41 0 0.005"/>
<geometry>
<box size="0.04 0.12 0.14" />
</geometry>
</collision>
</link>
<joint name="lidar_joint" type="fixed">
<parent link="trunk"/>
<child link="lidar_link"/>
<origin rpy="0 0 0" xyz="0.34218 0 0.17851"/>
</joint>
<link name="lidar_link">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="6.55E-08" />
<inertia
ixx="1.64E-15"
ixy="0"
ixz="-1.09E-47"
iyy="1.64E-15"
iyz="-1.32E-47"
izz="1.64E-15" />
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.02"/>
<geometry>
<cylinder length="0.16" radius="0.076" />
</geometry>
</collision>
</link>
<joint name="tail_joint" type="fixed">
<parent link="trunk"/>
<child link="tail_link"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<link name="tail_link">
<inertial>
<origin rpy="0 0 0" xyz="-0.37448 0.000488 0.006495"/>
<mass value="0.777" />
<inertia
ixx="0.0028118"
ixy="1.95E-05"
ixz="-7.87E-06"
iyy="0.0047506"
iyz="-1.57E-05"
izz="0.0029154" />
</inertial>
<collision>
<origin rpy="0 0 0" xyz="-0.405 0 0.005"/>
<geometry>
<box size="0.025 0.12 0.14" />
</geometry>
</collision>
</link>
<xacro:leg name="FR" mirror="-1" mirror_dae= "False" front_hind="1" front_hind_dae="True" />
<xacro:leg name="FL" mirror="1" mirror_dae="True" front_hind="1" front_hind_dae="True" />
<xacro:leg name="RR" mirror="-1" mirror_dae="False" front_hind="-1" front_hind_dae="False" />
<xacro:leg name="RL" mirror="1" mirror_dae="True" front_hind="-1" front_hind_dae="False" />
<!-- <xacro:stairs stairs="15" xpos="0" ypos="2.0" zpos="0" /> -->
</robot>

View File

@ -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>

View File

@ -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>

View File

@ -0,0 +1,6 @@
## b2 mujoco
##
1. install mujoco
2. enter "b2_description_mujoco" file
3. input "simulate ./xml/scene.xml" in your terminal to open b2 mujoco

Binary file not shown.

After

Width:  |  Height:  |  Size: 520 KiB

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,107 @@
# Blender 3.6.0
# www.blender.org
mtllib 20231207_1950front_camera_up.mtl
o mujoco_front_camera
v 0.417823 0.033470 0.060574
v 0.424611 0.033470 0.067362
v 0.416373 0.032921 0.059124
v 0.417115 0.033470 0.061281
v 0.423904 0.033470 0.068069
v 0.415666 0.032921 0.059831
v 0.414605 0.031420 0.058770
v 0.415312 0.031420 0.058063
v 0.414216 0.029370 0.058382
v 0.414923 0.029370 0.057675
v 0.414216 -0.029230 0.058382
v 0.414605 -0.031280 0.058770
v 0.414923 -0.029230 0.057675
v 0.415312 -0.031280 0.058063
v 0.416373 -0.032781 0.059124
v 0.415666 -0.032781 0.059831
v 0.417823 -0.033330 0.060574
v 0.424611 -0.033330 0.067362
v 0.417115 -0.033330 0.061281
v 0.423904 -0.033330 0.068069
v 0.425353 -0.032781 0.069519
v 0.426060 -0.032781 0.068812
v 0.426414 -0.031280 0.070580
v 0.426803 -0.029230 0.070968
v 0.427122 -0.031280 0.069873
v 0.427510 -0.029230 0.070261
v 0.427510 0.029370 0.070261
v 0.427122 0.031420 0.069873
v 0.426803 0.029370 0.070968
v 0.426414 0.031420 0.070580
v 0.425353 0.032921 0.069519
v 0.426060 0.032921 0.068812
vn -0.0000 1.0000 -0.0000
vn 0.7071 -0.0000 -0.7071
vn -0.3535 0.8660 -0.3536
vn -0.7071 -0.0000 0.7071
vn -0.6124 0.4999 -0.6124
vn -0.6124 0.5000 -0.6124
vn -0.7071 -0.0000 -0.7071
vn -0.6124 -0.4999 -0.6124
vn -0.6124 -0.5000 -0.6124
vn -0.3535 -0.8660 -0.3536
vn -0.0000 -1.0000 -0.0000
vn 0.0001 -1.0000 -0.0000
vn 0.3535 -0.8660 0.3536
vn 0.3534 -0.8660 0.3536
vn 0.6124 -0.5000 0.6124
vn 0.6125 -0.5001 0.6122
vn 0.7070 -0.0000 0.7072
vn 0.7071 -0.0000 0.7071
vn 0.6124 0.5000 0.6124
vn 0.3535 0.8660 0.3537
vn 0.3534 0.8660 0.3536
vt 0.000000 0.000000
vt 1.000000 0.000000
vt 1.000000 1.000000
vt 0.000000 1.000000
vt 0.230337 0.000000
vt 0.769663 0.000000
vt 0.884829 0.008223
vt 0.969140 0.030688
vt 1.000000 0.061377
vt 1.000000 0.938623
vt 0.969143 0.969310
vt 0.884833 0.991777
vt 0.769663 1.000000
vt 0.230337 1.000000
vt 0.115171 0.991777
vt 0.030860 0.969312
vt 0.000000 0.938623
vt 0.000000 0.061377
vt 0.030857 0.030690
vt 0.115167 0.008223
vt 0.658920 1.000000
vt 0.658920 0.000000
vt 0.341083 1.000000
vt 0.341083 0.000000
vt 0.000022 0.000000
vt 0.000022 1.000000
vt 0.341082 1.000000
vt 0.341082 0.000000
vt 0.000012 0.000000
vt 0.000012 1.000000
s 1
usemtl 材质.017
f 4/1/1 5/2/1 2/3/1 1/4/1
f 1/5/2 2/6/2 32/7/2 28/8/2 27/9/2 26/10/2 25/11/2 22/12/2 18/13/2 17/14/2 15/15/2 14/16/2 13/17/2 10/18/2 8/19/2 3/20/2
f 6/21/3 4/3/1 1/2/1 3/22/3
f 20/13/4 21/12/4 23/11/4 24/10/4 29/9/4 30/8/4 31/7/4 5/6/4 4/5/4 6/20/4 7/19/4 9/18/4 11/17/4 12/16/4 16/15/4 19/14/4
f 7/23/5 6/21/3 3/22/3 8/24/6
f 8/24/6 10/25/7 9/26/7 7/23/5
f 11/1/7 9/2/7 10/3/7 13/4/7
f 12/21/8 11/3/7 13/2/7 14/22/9
f 16/27/10 12/21/8 14/22/9 15/28/10
f 15/28/10 17/29/11 19/30/12 16/27/10
f 20/1/11 19/2/12 17/3/11 18/4/11
f 21/21/13 20/3/11 18/2/11 22/22/14
f 23/23/15 21/21/13 22/22/14 25/24/16
f 25/24/16 26/25/17 24/26/18 23/23/15
f 26/3/17 27/4/18 29/1/17 24/2/18
f 30/21/19 29/3/17 27/2/18 28/22/19
f 31/27/20 30/21/19 28/22/19 32/28/21
f 32/28/21 2/29/1 5/30/1 31/27/20

View File

@ -0,0 +1,270 @@
# Blender 3.6.0
# www.blender.org
mtllib 20231207_1950front_camera.mtl
o mujoco_front_circle_camera
v 0.419269 -0.013139 -0.025418
v 0.419269 -0.009394 -0.028384
v 0.417269 -0.013139 -0.025418
v 0.419269 -0.015988 -0.021583
v 0.417269 -0.015988 -0.021583
v 0.419269 -0.017748 -0.017142
v 0.417269 -0.017748 -0.017142
v 0.419269 -0.018298 -0.012396
v 0.417269 -0.018298 -0.012396
v 0.419269 -0.017601 -0.007670
v 0.417269 -0.017601 -0.007670
v 0.419269 -0.015705 -0.003285
v 0.417269 -0.015705 -0.003285
v 0.419269 -0.012738 0.000459
v 0.419269 -0.013087 -0.004851
v 0.419269 -0.008653 -0.000122
v 0.419269 -0.014068 -0.006793
v 0.419269 -0.015017 -0.015334
v 0.421269 -0.014068 -0.006793
v 0.421269 -0.008653 -0.000122
v 0.421269 -0.015017 -0.015334
v 0.421269 -0.011198 -0.023031
v 0.419269 -0.011198 -0.023031
v 0.421269 -0.003824 -0.027442
v 0.419269 -0.003824 -0.027442
v 0.421269 0.004764 -0.027166
v 0.421269 0.011840 -0.022291
v 0.419269 0.004764 -0.027166
v 0.419269 0.011840 -0.022291
v 0.419269 0.013087 -0.020508
v 0.419269 0.015157 -0.014364
v 0.419269 0.015705 -0.022073
v 0.419269 0.017601 -0.017689
v 0.417269 0.015705 -0.022073
v 0.419269 0.012738 -0.025818
v 0.417269 0.012738 -0.025818
v 0.419269 0.008904 -0.028667
v 0.417269 0.008904 -0.028667
v 0.419269 0.004462 -0.030427
v 0.417269 0.004462 -0.030427
v 0.419269 -0.000283 -0.030977
v 0.417269 -0.000283 -0.030977
v 0.419269 -0.005009 -0.030281
v 0.417269 -0.005009 -0.030281
v 0.417269 -0.009394 -0.028384
v 0.417269 0.017601 -0.017689
v 0.417269 0.018298 -0.012962
v 0.417269 0.017748 -0.008217
v 0.419269 0.018298 -0.012962
v 0.419269 0.017748 -0.008217
v 0.419269 0.015988 -0.003776
v 0.419269 0.013139 0.000059
v 0.417269 0.015988 -0.003776
v 0.417269 0.013139 0.000059
v 0.417269 0.009394 0.003025
v 0.417269 0.005009 0.004922
v 0.419269 0.009394 0.003025
v 0.419269 0.005009 0.004922
v 0.419269 0.000283 0.005618
v 0.419269 -0.004462 0.005068
v 0.417269 0.000283 0.005618
v 0.417269 -0.004462 0.005068
v 0.417269 -0.008904 0.003308
v 0.417269 -0.012738 0.000459
v 0.419269 -0.008904 0.003308
v 0.419269 0.013661 -0.005902
v 0.421269 0.015157 -0.014364
v 0.421269 0.013661 -0.005902
v 0.421269 0.007828 0.000408
v 0.419269 0.007828 0.000408
v 0.421269 -0.000490 0.002563
v 0.419269 -0.000490 0.002563
vn 1.0000 -0.0000 -0.0000
vn -0.0000 -0.7179 -0.6961
vn -0.0000 -0.5133 -0.8582
vn -0.0000 -0.8737 -0.4865
vn -0.0000 -0.9698 -0.2439
vn -0.0000 -0.9999 0.0155
vn -0.0000 -0.9618 0.2737
vn -0.0000 -0.8582 0.5134
vn -0.0000 -0.6960 0.7180
vn -0.0000 -0.9225 0.3860
vn -0.0000 -0.5674 0.8234
vn -0.0000 -0.8582 0.5133
vn -0.0000 -0.9847 -0.1741
vn -0.0000 -0.7343 -0.6788
vn -0.0000 -0.2508 -0.9680
vn -0.0000 0.3124 -0.9500
vn -0.0000 0.7764 -0.6302
vn -0.0000 0.9939 -0.1104
vn -0.0000 0.8582 -0.5133
vn -0.0000 0.8582 -0.5134
vn -0.0000 0.9618 -0.2738
vn -0.0000 0.6961 -0.7180
vn -0.0000 0.4866 -0.8736
vn -0.0000 0.2438 -0.9698
vn -0.0000 -0.0154 -0.9999
vn -0.0000 -0.2737 -0.9618
vn -1.0000 -0.0000 -0.0000
vn -0.0000 0.9999 -0.0155
vn -0.0000 0.9698 0.2439
vn -0.0000 0.8737 0.4865
vn -0.0000 0.7180 0.6961
vn -0.0000 0.5133 0.8582
vn -0.0000 0.2737 0.9618
vn -0.0000 0.0154 0.9999
vn -0.0000 -0.2438 0.9698
vn -0.0000 -0.4866 0.8736
vn -0.0000 0.8958 0.4445
vn -0.0000 -0.0321 0.9995
vt 0.500000 0.916667
vt 0.559298 0.912426
vt 0.772859 0.814896
vt 0.899789 0.617388
vt 0.899789 0.382612
vt 0.772859 0.185104
vt 0.559298 0.087574
vt 0.500000 0.083333
vt 0.500000 0.000000
vt 0.629409 0.017037
vt 0.750000 0.066987
vt 0.853553 0.146447
vt 0.933013 0.250000
vt 0.982963 0.370591
vt 1.000000 0.500000
vt 0.982963 0.629409
vt 0.933013 0.750000
vt 0.853553 0.853553
vt 0.750000 0.933013
vt 0.629409 0.982963
vt 0.500000 1.000000
vt 0.044139 0.000000
vt 0.000000 0.000000
vt 0.000000 1.000000
vt 0.044139 1.000000
vt 0.085270 0.000000
vt 0.085270 1.000000
vt 0.125000 0.000000
vt 0.125000 1.000000
vt 0.164730 0.000000
vt 0.164730 1.000000
vt 0.205861 0.000000
vt 0.205861 1.000000
vt 0.250000 0.000000
vt 0.250000 1.000000
vt 0.294139 0.000000
vt 0.294139 1.000000
vt 0.326911 0.120987
vt 0.149478 0.274733
vt 0.083333 0.500000
vt 0.149478 0.725267
vt 0.326911 0.879013
vt 0.370591 0.982963
vt 0.250000 0.933013
vt 0.146447 0.853553
vt 0.066987 0.750000
vt 0.017037 0.629409
vt 0.000000 0.500000
vt 0.017037 0.370591
vt 0.066987 0.250000
vt 0.146447 0.146447
vt 0.250000 0.066987
vt 0.370591 0.017037
vt 0.274559 0.000000
vt 0.179447 0.000000
vt 0.179447 1.000000
vt 0.274559 1.000000
vt 0.364222 0.000000
vt 0.364222 1.000000
vt 0.920627 0.229680
vt 0.707707 0.045184
vt 0.428843 0.005089
vt 0.172570 0.122125
vt 0.020253 0.359134
vt 0.020253 0.640866
vt 0.172570 0.877875
vt 0.428843 0.994911
vt 0.707707 0.954816
vt 0.920627 0.770320
vt 0.452024 0.000000
vt 0.452024 1.000000
vt 0.547976 0.000000
vt 0.547976 1.000000
vt 0.635778 0.000000
vt 0.635778 1.000000
vt 0.725441 0.000000
vt 0.725441 1.000000
vt 0.820553 0.000000
vt 0.750000 1.000000
vt 0.820553 1.000000
vt 0.750000 0.000000
vt 0.705861 0.000000
vt 0.705861 1.000000
vt 0.794139 0.000000
vt 0.794139 1.000000
vt 0.835270 0.000000
vt 0.835270 1.000000
vt 0.875000 0.000000
vt 0.875000 1.000000
vt 0.914730 0.000000
vt 0.914730 1.000000
vt 0.955861 0.000000
vt 0.955861 1.000000
vt 1.000000 1.000000
vt 1.000000 0.000000
vt 0.664730 0.000000
vt 0.664730 1.000000
vt 0.625000 0.000000
vt 0.625000 1.000000
vt 0.585270 0.000000
vt 0.585270 1.000000
vt 0.544139 0.000000
vt 0.544139 1.000000
vt 0.455861 0.000000
vt 0.455861 1.000000
vt 0.414730 0.000000
vt 0.414730 1.000000
vt 0.375000 0.000000
vt 0.375000 1.000000
vt 0.335270 0.000000
vt 0.335270 1.000000
vt 0.907444 0.000000
vt 0.907444 1.000000
vt 0.092556 0.000000
vt 0.092556 1.000000
s 1
usemtl 材质.019
f 30/1/1 29/2/1 28/3/1 25/4/1 23/5/1 18/6/1 17/7/1 15/8/1 12/9/1 10/10/1 8/11/1 6/12/1 4/13/1 1/14/1 2/15/1 43/16/1 41/17/1 39/18/1 37/19/1 35/20/1 32/21/1
f 3/22/2 45/23/3 2/24/3 1/25/2
f 5/26/4 3/22/2 1/25/2 4/27/4
f 7/28/5 5/26/4 4/27/4 6/29/5
f 9/30/6 7/28/5 6/29/5 8/31/6
f 11/32/7 9/30/6 8/31/6 10/33/7
f 13/34/8 11/32/7 10/33/7 12/35/8
f 64/36/9 13/34/8 12/35/8 14/37/9
f 15/8/1 16/38/1 72/39/1 70/40/1 66/41/1 31/42/1 30/1/1 32/21/1 33/43/1 49/44/1 50/45/1 51/46/1 52/47/1 57/48/1 58/49/1 59/50/1 60/51/1 65/52/1 14/53/1 12/9/1
f 19/54/10 20/55/11 16/56/11 15/35/12 17/57/10
f 21/58/13 19/54/10 17/57/10 18/59/13
f 69/15/1 71/60/1 20/61/1 19/62/1 21/63/1 22/64/1 24/65/1 26/66/1 27/67/1 67/68/1 68/69/1
f 22/70/14 21/58/13 18/59/13 23/71/14
f 24/72/15 22/70/14 23/71/14 25/73/15
f 26/74/16 24/72/15 25/73/15 28/75/16
f 27/76/17 26/74/16 28/75/16 29/77/17
f 67/78/18 27/76/17 29/77/17 30/79/19 31/80/18
f 34/81/20 46/82/21 33/83/21 32/79/20
f 36/84/22 34/81/20 32/79/20 35/85/22
f 38/86/23 36/84/22 35/85/22 37/87/23
f 40/88/24 38/86/23 37/87/23 39/89/24
f 42/90/25 40/88/24 39/89/24 41/91/25
f 44/92/26 42/90/25 41/91/25 43/93/26
f 43/93/26 2/94/3 45/95/3 44/92/26
f 45/15/27 3/14/27 5/13/27 7/12/27 9/11/27 11/10/27 13/9/27 64/53/27 63/52/27 62/51/27 61/50/27 56/49/27 55/48/27 54/47/27 53/46/27 48/45/27 47/44/27 46/43/27 34/21/27 36/20/27 38/19/27 40/18/27 42/17/27 44/16/27
f 46/82/21 47/96/28 49/97/28 33/83/21
f 47/96/28 48/98/29 50/99/29 49/97/28
f 48/98/29 53/100/30 51/101/30 50/99/29
f 53/100/30 54/102/31 52/103/31 51/101/30
f 54/102/31 55/9/32 57/21/32 52/103/31
f 55/9/32 56/104/33 58/105/33 57/21/32
f 56/104/33 61/106/34 59/107/34 58/105/33
f 61/106/34 62/108/35 60/109/35 59/107/34
f 62/108/35 63/110/36 65/111/36 60/109/35
f 63/110/36 64/36/9 14/37/9 65/111/36
f 68/112/37 67/78/18 31/80/18 66/113/37
f 66/113/37 70/94/32 69/95/32 68/112/37
f 71/114/38 69/23/32 70/24/32 72/115/38
f 20/55/11 71/114/38 72/115/38 16/56/11

Binary file not shown.

Binary file not shown.

Binary file not shown.

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,102 @@
# Blender 3.6.0
# www.blender.org
mtllib 20231207_1950back_camera_up.mtl
o mujoco_back_camera
v -0.410810 0.033470 0.030300
v -0.417598 0.033470 0.037088
v -0.409361 0.032921 0.028850
v -0.410103 0.033470 0.031007
v -0.416891 0.033470 0.037795
v -0.408654 0.032921 0.029558
v -0.407592 0.031420 0.028496
v -0.407204 0.029370 0.028108
v -0.408300 0.031420 0.027789
v -0.407911 0.029370 0.027401
v -0.407911 -0.029230 0.027401
v -0.408300 -0.031280 0.027789
v -0.407204 -0.029230 0.028108
v -0.407592 -0.031280 0.028496
v -0.408654 -0.032781 0.029558
v -0.409361 -0.032781 0.028850
v -0.410103 -0.033330 0.031007
v -0.416891 -0.033330 0.037795
v -0.410810 -0.033330 0.030300
v -0.417598 -0.033330 0.037088
v -0.419048 -0.032781 0.038538
v -0.420109 -0.031280 0.039599
v -0.418341 -0.032781 0.039245
v -0.419402 -0.031280 0.040306
v -0.419791 -0.029230 0.040695
v -0.419791 0.029370 0.040695
v -0.420498 -0.029230 0.039987
v -0.420498 0.029370 0.039987
v -0.420109 0.031420 0.039599
v -0.419048 0.032921 0.038538
v -0.419402 0.031420 0.040306
v -0.418341 0.032921 0.039245
vn -0.0000 1.0000 -0.0000
vn -0.0001 1.0000 -0.0001
vn -0.7071 -0.0000 -0.7071
vn 0.3536 0.8660 -0.3536
vn 0.3535 0.8661 -0.3534
vn 0.7071 -0.0000 0.7071
vn 0.6122 0.5001 -0.6125
vn 0.6123 0.4999 -0.6125
vn 0.7070 -0.0000 -0.7072
vn 0.7071 -0.0000 -0.7071
vn 0.6122 -0.5001 -0.6125
vn 0.6125 -0.5001 -0.6121
vn 0.3536 -0.8660 -0.3536
vn -0.0000 -1.0000 -0.0000
vn -0.0000 -1.0000 -0.0001
vn -0.3535 -0.8660 0.3535
vn -0.6123 -0.5000 0.6125
vn -0.6125 -0.5000 0.6122
vn -0.7075 -0.0000 0.7067
vn -0.7071 -0.0000 0.7071
vn -0.6125 0.5000 0.6122
vn -0.3535 0.8660 0.3535
vt 0.000000 1.000000
vt 1.000000 1.000000
vt 1.000000 0.000000
vt 0.000000 0.000000
vt 0.000000 0.061377
vt 0.000000 0.938623
vt 0.030859 0.969311
vt 0.115169 0.991777
vt 0.230337 1.000000
vt 0.769663 1.000000
vt 0.884831 0.991777
vt 0.969141 0.969311
vt 1.000000 0.938623
vt 1.000000 0.061377
vt 0.969141 0.030689
vt 0.884831 0.008223
vt 0.769663 0.000000
vt 0.230337 0.000000
vt 0.115169 0.008223
vt 0.030859 0.030689
vt 0.658919 0.000000
vt 0.658919 1.000000
vt 0.341081 0.000000
vt 0.341081 1.000000
s 1
usemtl 材质.018
f 1/1/1 2/2/1 5/3/1 4/4/2
f 10/5/3 11/6/3 12/7/3 16/8/3 19/9/3 20/10/3 21/11/3 22/12/3 27/13/3 28/14/3 29/15/3 30/16/3 2/17/3 1/18/3 3/19/3 9/20/3
f 3/21/4 1/3/1 4/2/2 6/22/5
f 17/9/6 15/8/6 14/7/6 13/6/6 8/5/6 7/20/6 6/19/6 4/18/6 5/17/6 32/16/6 31/15/6 26/14/6 25/13/6 24/12/6 23/11/6 18/10/6
f 9/23/7 3/21/4 6/22/5 7/24/8
f 7/24/8 8/1/9 10/4/10 9/23/7
f 11/1/9 10/2/10 8/3/9 13/4/10
f 12/21/11 11/3/9 13/2/10 14/22/12
f 16/23/13 12/21/11 14/22/12 15/24/13
f 15/24/13 17/1/14 19/4/14 16/23/13
f 20/1/14 19/2/14 17/3/14 18/4/15
f 21/21/16 20/3/14 18/2/15 23/22/16
f 22/23/17 21/21/16 23/22/16 24/24/18
f 24/24/18 25/1/19 27/4/20 22/23/17
f 25/3/19 26/4/20 28/1/19 27/2/20
f 29/21/21 28/3/19 26/2/20 31/22/21
f 30/23/22 29/21/21 31/22/21 32/24/22
f 32/24/22 5/1/1 2/4/1 30/23/22

View File

@ -0,0 +1,270 @@
# Blender 3.6.0
# www.blender.org
mtllib 20231207_1950back_camera.mtl
o mujoco_back_circle_camera
v -0.411269 0.013139 -0.037918
v -0.411269 0.009394 -0.040884
v -0.409269 0.013139 -0.037918
v -0.411269 0.015988 -0.034083
v -0.409269 0.015988 -0.034083
v -0.411269 0.017748 -0.029642
v -0.409269 0.017748 -0.029642
v -0.411269 0.018298 -0.024896
v -0.409269 0.018298 -0.024896
v -0.411269 0.017601 -0.020170
v -0.409269 0.017601 -0.020170
v -0.411269 0.015705 -0.015785
v -0.409269 0.015705 -0.015785
v -0.411269 0.012738 -0.012041
v -0.411269 0.013087 -0.017351
v -0.411269 0.008653 -0.012622
v -0.411269 0.014068 -0.019293
v -0.411269 0.015017 -0.027834
v -0.413269 0.014068 -0.019293
v -0.413269 0.008653 -0.012622
v -0.413269 0.015017 -0.027834
v -0.413269 0.011198 -0.035531
v -0.411269 0.011198 -0.035531
v -0.413269 0.003824 -0.039942
v -0.411269 0.003824 -0.039942
v -0.413269 -0.004764 -0.039666
v -0.413269 -0.011840 -0.034791
v -0.411269 -0.004764 -0.039666
v -0.411269 -0.011840 -0.034791
v -0.411269 -0.013087 -0.033008
v -0.411269 -0.015157 -0.026864
v -0.411269 -0.015705 -0.034573
v -0.411269 -0.017601 -0.030189
v -0.409269 -0.015705 -0.034573
v -0.411269 -0.012738 -0.038318
v -0.409269 -0.012738 -0.038318
v -0.411269 -0.008904 -0.041167
v -0.409269 -0.008904 -0.041167
v -0.411269 -0.004462 -0.042927
v -0.409269 -0.004462 -0.042927
v -0.411269 0.000283 -0.043477
v -0.409269 0.000283 -0.043477
v -0.411269 0.005009 -0.042781
v -0.409269 0.005009 -0.042781
v -0.409269 0.009394 -0.040884
v -0.409269 -0.017601 -0.030189
v -0.409269 -0.018298 -0.025462
v -0.409269 -0.017748 -0.020717
v -0.411269 -0.018298 -0.025462
v -0.411269 -0.017748 -0.020717
v -0.411269 -0.015988 -0.016276
v -0.411269 -0.013139 -0.012441
v -0.409269 -0.015988 -0.016276
v -0.409269 -0.013139 -0.012441
v -0.409269 -0.009394 -0.009475
v -0.409269 -0.005009 -0.007578
v -0.411269 -0.009394 -0.009475
v -0.411269 -0.005009 -0.007578
v -0.411269 -0.000283 -0.006882
v -0.411269 0.004462 -0.007432
v -0.409269 -0.000283 -0.006882
v -0.409269 0.004462 -0.007432
v -0.409269 0.008904 -0.009192
v -0.409269 0.012738 -0.012041
v -0.411269 0.008904 -0.009192
v -0.411269 -0.013661 -0.018402
v -0.413269 -0.015157 -0.026864
v -0.413269 -0.013661 -0.018402
v -0.413269 -0.007828 -0.012092
v -0.411269 -0.007828 -0.012092
v -0.413269 0.000490 -0.009937
v -0.411269 0.000490 -0.009937
vn -1.0000 -0.0000 -0.0000
vn -0.0000 0.7179 -0.6961
vn -0.0000 0.5133 -0.8582
vn -0.0000 0.8737 -0.4865
vn -0.0000 0.9698 -0.2439
vn -0.0000 0.9999 0.0155
vn -0.0000 0.9618 0.2737
vn -0.0000 0.8582 0.5134
vn -0.0000 0.6960 0.7180
vn -0.0000 0.9225 0.3860
vn -0.0000 0.5674 0.8234
vn -0.0000 0.8582 0.5133
vn -0.0000 0.9847 -0.1741
vn -0.0000 0.7343 -0.6788
vn -0.0000 0.2508 -0.9680
vn -0.0000 -0.3124 -0.9500
vn -0.0000 -0.7764 -0.6302
vn -0.0000 -0.9939 -0.1104
vn -0.0000 -0.8582 -0.5133
vn -0.0000 -0.8582 -0.5134
vn -0.0000 -0.9618 -0.2738
vn -0.0000 -0.6961 -0.7180
vn -0.0000 -0.4866 -0.8736
vn -0.0000 -0.2438 -0.9698
vn -0.0000 0.0154 -0.9999
vn -0.0000 0.2737 -0.9618
vn 1.0000 -0.0000 -0.0000
vn -0.0000 -0.9999 -0.0155
vn -0.0000 -0.9698 0.2439
vn -0.0000 -0.8737 0.4865
vn -0.0000 -0.7180 0.6961
vn -0.0000 -0.5133 0.8582
vn -0.0000 -0.2737 0.9618
vn -0.0000 -0.0154 0.9999
vn -0.0000 0.2438 0.9698
vn -0.0000 0.4866 0.8736
vn -0.0000 -0.8958 0.4445
vn -0.0000 0.0321 0.9995
vt 0.500000 0.916667
vt 0.559298 0.912426
vt 0.772859 0.814896
vt 0.899789 0.617388
vt 0.899789 0.382612
vt 0.772859 0.185104
vt 0.559298 0.087574
vt 0.500000 0.083333
vt 0.500000 0.000000
vt 0.629409 0.017037
vt 0.750000 0.066987
vt 0.853553 0.146447
vt 0.933013 0.250000
vt 0.982963 0.370591
vt 1.000000 0.500000
vt 0.982963 0.629409
vt 0.933013 0.750000
vt 0.853553 0.853553
vt 0.750000 0.933013
vt 0.629409 0.982963
vt 0.500000 1.000000
vt 0.044139 0.000000
vt 0.000000 0.000000
vt 0.000000 1.000000
vt 0.044139 1.000000
vt 0.085270 0.000000
vt 0.085270 1.000000
vt 0.125000 0.000000
vt 0.125000 1.000000
vt 0.164730 0.000000
vt 0.164730 1.000000
vt 0.205861 0.000000
vt 0.205861 1.000000
vt 0.250000 0.000000
vt 0.250000 1.000000
vt 0.294139 0.000000
vt 0.294139 1.000000
vt 0.326911 0.120987
vt 0.149478 0.274733
vt 0.083333 0.500000
vt 0.149478 0.725267
vt 0.326911 0.879013
vt 0.370591 0.982963
vt 0.250000 0.933013
vt 0.146447 0.853553
vt 0.066987 0.750000
vt 0.017037 0.629409
vt 0.000000 0.500000
vt 0.017037 0.370591
vt 0.066987 0.250000
vt 0.146447 0.146447
vt 0.250000 0.066987
vt 0.370591 0.017037
vt 0.274559 0.000000
vt 0.179447 0.000000
vt 0.179447 1.000000
vt 0.274559 1.000000
vt 0.364222 0.000000
vt 0.364222 1.000000
vt 0.920627 0.229680
vt 0.707707 0.045184
vt 0.428843 0.005089
vt 0.172570 0.122125
vt 0.020253 0.359134
vt 0.020253 0.640866
vt 0.172570 0.877875
vt 0.428843 0.994911
vt 0.707707 0.954816
vt 0.920627 0.770320
vt 0.452024 0.000000
vt 0.452024 1.000000
vt 0.547976 0.000000
vt 0.547976 1.000000
vt 0.635778 0.000000
vt 0.635778 1.000000
vt 0.725441 0.000000
vt 0.725441 1.000000
vt 0.820553 0.000000
vt 0.750000 1.000000
vt 0.820553 1.000000
vt 0.750000 0.000000
vt 0.705861 0.000000
vt 0.705861 1.000000
vt 0.794139 0.000000
vt 0.794139 1.000000
vt 0.835270 0.000000
vt 0.835270 1.000000
vt 0.875000 0.000000
vt 0.875000 1.000000
vt 0.914730 0.000000
vt 0.914730 1.000000
vt 0.955861 0.000000
vt 0.955861 1.000000
vt 1.000000 1.000000
vt 1.000000 0.000000
vt 0.664730 0.000000
vt 0.664730 1.000000
vt 0.625000 0.000000
vt 0.625000 1.000000
vt 0.585270 0.000000
vt 0.585270 1.000000
vt 0.544139 0.000000
vt 0.544139 1.000000
vt 0.455861 0.000000
vt 0.455861 1.000000
vt 0.414730 0.000000
vt 0.414730 1.000000
vt 0.375000 0.000000
vt 0.375000 1.000000
vt 0.335270 0.000000
vt 0.335270 1.000000
vt 0.907444 0.000000
vt 0.907444 1.000000
vt 0.092556 0.000000
vt 0.092556 1.000000
s 1
usemtl 材质.020
f 30/1/1 29/2/1 28/3/1 25/4/1 23/5/1 18/6/1 17/7/1 15/8/1 12/9/1 10/10/1 8/11/1 6/12/1 4/13/1 1/14/1 2/15/1 43/16/1 41/17/1 39/18/1 37/19/1 35/20/1 32/21/1
f 3/22/2 45/23/3 2/24/3 1/25/2
f 5/26/4 3/22/2 1/25/2 4/27/4
f 7/28/5 5/26/4 4/27/4 6/29/5
f 9/30/6 7/28/5 6/29/5 8/31/6
f 11/32/7 9/30/6 8/31/6 10/33/7
f 13/34/8 11/32/7 10/33/7 12/35/8
f 64/36/9 13/34/8 12/35/8 14/37/9
f 15/8/1 16/38/1 72/39/1 70/40/1 66/41/1 31/42/1 30/1/1 32/21/1 33/43/1 49/44/1 50/45/1 51/46/1 52/47/1 57/48/1 58/49/1 59/50/1 60/51/1 65/52/1 14/53/1 12/9/1
f 19/54/10 20/55/11 16/56/11 15/35/12 17/57/10
f 21/58/13 19/54/10 17/57/10 18/59/13
f 69/15/1 71/60/1 20/61/1 19/62/1 21/63/1 22/64/1 24/65/1 26/66/1 27/67/1 67/68/1 68/69/1
f 22/70/14 21/58/13 18/59/13 23/71/14
f 24/72/15 22/70/14 23/71/14 25/73/15
f 26/74/16 24/72/15 25/73/15 28/75/16
f 27/76/17 26/74/16 28/75/16 29/77/17
f 67/78/18 27/76/17 29/77/17 30/79/19 31/80/18
f 34/81/20 46/82/21 33/83/21 32/79/20
f 36/84/22 34/81/20 32/79/20 35/85/22
f 38/86/23 36/84/22 35/85/22 37/87/23
f 40/88/24 38/86/23 37/87/23 39/89/24
f 42/90/25 40/88/24 39/89/24 41/91/25
f 44/92/26 42/90/25 41/91/25 43/93/26
f 43/93/26 2/94/3 45/95/3 44/92/26
f 45/15/27 3/14/27 5/13/27 7/12/27 9/11/27 11/10/27 13/9/27 64/53/27 63/52/27 62/51/27 61/50/27 56/49/27 55/48/27 54/47/27 53/46/27 48/45/27 47/44/27 46/43/27 34/21/27 36/20/27 38/19/27 40/18/27 42/17/27 44/16/27
f 46/82/21 47/96/28 49/97/28 33/83/21
f 47/96/28 48/98/29 50/99/29 49/97/28
f 48/98/29 53/100/30 51/101/30 50/99/29
f 53/100/30 54/102/31 52/103/31 51/101/30
f 54/102/31 55/9/32 57/21/32 52/103/31
f 55/9/32 56/104/33 58/105/33 57/21/32
f 56/104/33 61/106/34 59/107/34 58/105/33
f 61/106/34 62/108/35 60/109/35 59/107/34
f 62/108/35 63/110/36 65/111/36 60/109/35
f 63/110/36 64/36/9 14/37/9 65/111/36
f 68/112/37 67/78/18 31/80/18 66/113/37
f 66/113/37 70/94/32 69/95/32 68/112/37
f 71/114/38 69/23/32 70/24/32 72/115/38
f 20/55/11 71/114/38 72/115/38 16/56/11

View File

@ -0,0 +1,319 @@
# Blender 3.6.0
# www.blender.org
mtllib mujocolidar2.mtl
o mujoco_lidar1
v -0.040416 0.012739 0.008240
v -0.035499 0.024610 0.008240
v -0.040793 0.012840 -0.014093
v -0.042094 0.000000 0.008240
v -0.040040 0.012638 0.030574
v -0.035162 0.024415 0.030574
v -0.041704 0.000000 0.030574
v -0.040040 -0.012638 0.030574
v -0.035162 -0.024415 0.030574
v -0.040417 -0.012738 0.008240
v -0.035500 -0.024610 0.008240
v -0.040793 -0.012839 -0.014093
v -0.041170 -0.012941 -0.036426
v -0.035837 -0.024805 -0.014093
v -0.042483 0.000000 -0.014093
v -0.042873 0.000000 -0.036426
v -0.041170 0.012941 -0.036426
v -0.036175 0.025000 -0.036426
v -0.035837 0.024805 -0.014093
v -0.028229 0.035355 -0.036426
v -0.027953 0.035080 -0.014093
v -0.017873 0.043301 -0.036426
v -0.017678 0.042964 -0.014093
v -0.005814 0.048296 -0.036426
v -0.005713 0.047920 -0.014093
v 0.007127 0.050000 -0.036426
v 0.007127 0.049610 -0.014093
v 0.020068 0.048296 -0.036426
v 0.019967 0.047920 -0.014093
v 0.032127 0.043301 -0.036426
v 0.031932 0.042964 -0.014093
v 0.042482 0.035355 -0.036426
v 0.042206 0.035080 -0.014093
v 0.050428 0.025000 -0.036426
v 0.050090 0.024805 -0.014093
v 0.055423 0.012941 -0.036426
v 0.055047 0.012840 -0.014093
v 0.057127 0.000000 -0.036426
v 0.056737 0.000000 -0.014093
v 0.055423 -0.012941 -0.036426
v 0.050428 -0.025000 -0.036426
v 0.055047 -0.012840 -0.014093
v 0.050090 -0.024805 -0.014093
v 0.054670 -0.012739 0.008240
v 0.054293 -0.012639 0.030574
v 0.056347 0.000000 0.008240
v 0.049753 -0.024610 0.008240
v 0.041931 -0.034804 0.008240
v 0.049415 -0.024415 0.030574
v 0.041655 -0.034529 0.030574
v 0.031542 -0.042289 0.030574
v 0.019765 -0.047167 0.030574
v 0.031737 -0.042626 0.008240
v 0.019866 -0.047543 0.008240
v 0.031932 -0.042964 -0.014093
v 0.032127 -0.043301 -0.036426
v 0.019966 -0.047920 -0.014093
v 0.042206 -0.035080 -0.014093
v 0.042482 -0.035355 -0.036426
v 0.020068 -0.048296 -0.036426
v 0.007126 -0.049610 -0.014093
v 0.007126 -0.050000 -0.036426
v -0.005714 -0.047920 -0.014093
v 0.007126 -0.049220 0.008240
v -0.005613 -0.047543 0.008240
v 0.007126 -0.048831 0.030574
v -0.005512 -0.047167 0.030574
v -0.017289 -0.042288 0.030574
v -0.027402 -0.034528 0.030574
v -0.017484 -0.042626 0.008240
v -0.027678 -0.034804 0.008240
v -0.017679 -0.042963 -0.014093
v -0.017874 -0.043301 -0.036426
v -0.027953 -0.035079 -0.014093
v -0.028229 -0.035355 -0.036426
v -0.036175 -0.025000 -0.036426
v -0.005815 -0.048296 -0.036426
v 0.054670 0.012739 0.008240
v 0.055957 0.000000 0.030574
v 0.054293 0.012638 0.030574
v 0.049415 0.024415 0.030574
v 0.041655 0.034528 0.030574
v 0.049753 0.024610 0.008240
v 0.041931 0.034804 0.008240
v 0.031737 0.042626 0.008240
v 0.019866 0.047543 0.008240
v 0.031542 0.042288 0.030574
v 0.019765 0.047167 0.030574
v 0.007127 0.048831 0.030574
v -0.005512 0.047167 0.030574
v 0.007127 0.049220 0.008240
v -0.005612 0.047543 0.008240
v -0.017483 0.042626 0.008240
v -0.027677 0.034804 0.008240
v -0.017289 0.042288 0.030574
v -0.027402 0.034528 0.030574
vn -0.9658 0.2588 0.0174
vn -0.8659 0.4999 0.0174
vn -0.8659 0.4999 0.0175
vn -0.9658 0.2588 0.0175
vn -0.9998 -0.0000 0.0175
vn -0.9998 -0.0000 0.0174
vn -0.0000 -0.0000 1.0000
vn -0.9658 -0.2588 0.0174
vn -0.9658 -0.2588 0.0175
vn -0.8659 -0.4999 0.0174
vn -0.8659 -0.4999 0.0175
vn -0.0000 -0.0000 -1.0000
vn -0.7070 0.7070 0.0174
vn -0.7070 0.7070 0.0175
vn -0.4999 0.8659 0.0174
vn -0.4999 0.8659 0.0175
vn -0.2588 0.9658 0.0174
vn -0.2588 0.9658 0.0175
vn -0.0000 0.9998 0.0174
vn -0.0000 0.9998 0.0175
vn 0.2588 0.9658 0.0174
vn 0.2588 0.9658 0.0175
vn 0.4999 0.8659 0.0174
vn 0.7070 0.7070 0.0174
vn 0.8659 0.4999 0.0175
vn 0.8659 0.4999 0.0174
vn 0.9658 0.2588 0.0174
vn 0.9658 0.2588 0.0175
vn 0.9998 -0.0000 0.0175
vn 0.9998 -0.0000 0.0174
vn 0.9658 -0.2588 0.0175
vn 0.9658 -0.2588 0.0174
vn 0.8659 -0.4999 0.0174
vn 0.8659 -0.4999 0.0175
vn 0.7070 -0.7070 0.0174
vn 0.4999 -0.8659 0.0174
vn 0.2588 -0.9658 0.0174
vn 0.2588 -0.9658 0.0175
vn -0.0000 -0.9998 0.0175
vn -0.0000 -0.9998 0.0174
vn -0.2588 -0.9658 0.0175
vn -0.2588 -0.9658 0.0174
vn -0.4999 -0.8659 0.0174
vn -0.4999 -0.8659 0.0175
vn -0.7070 -0.7070 0.0174
vn -0.7070 -0.7070 0.0175
vn 0.7070 0.7070 0.0175
vn 0.4999 0.8659 0.0175
vt 0.088278 0.000000
vt 0.170540 0.000000
vt 0.170540 0.333333
vt 0.088278 0.333333
vt 0.170540 0.666667
vt 0.088278 0.666667
vt 0.000000 0.666667
vt 0.000000 0.333333
vt 0.000000 0.000000
vt 0.000000 0.500000
vt 0.017035 0.370597
vt 0.066984 0.250005
vt 0.146443 0.146450
vt 0.249996 0.066990
vt 0.370587 0.017038
vt 0.499996 0.000000
vt 0.629406 0.017036
vt 0.749998 0.066986
vt 0.853552 0.146445
vt 0.933012 0.249999
vt 0.982963 0.370590
vt 1.000000 0.500000
vt 0.982963 0.629409
vt 0.933013 0.750000
vt 0.853553 0.853553
vt 0.750000 0.933013
vt 0.629409 0.982963
vt 0.500000 1.000000
vt 0.370591 0.982963
vt 0.250000 0.933013
vt 0.146447 0.853553
vt 0.066987 0.750000
vt 0.017037 0.629409
vt 0.000005 0.000000
vt 0.000005 0.333333
vt 0.170541 0.333333
vt 0.170541 0.000000
vt 0.000005 0.666667
vt 0.170541 0.666667
vt 0.088278 1.000000
vt 0.170541 1.000000
vt 0.000005 1.000000
vt 0.000000 1.000000
vt 0.170540 1.000000
vt 0.250000 1.000000
vt 0.250000 0.666667
vt 0.329459 1.000000
vt 0.329459 0.666667
vt 0.411722 1.000000
vt 0.411722 0.666667
vt 0.500000 0.666667
vt 0.588278 1.000000
vt 0.588278 0.666667
vt 0.670541 1.000000
vt 0.670541 0.666667
vt 0.750000 1.000000
vt 0.750000 0.666667
vt 0.829459 1.000000
vt 0.829459 0.666667
vt 0.911722 1.000000
vt 0.911722 0.666667
vt 1.000000 0.666667
vt 1.000000 1.000000
vt 0.829460 0.666667
vt 0.829460 1.000000
vt 0.911722 0.333333
vt 1.000000 0.333333
vt 0.829460 0.333333
vt 0.911722 0.000000
vt 0.829460 0.000000
vt 1.000000 0.000000
vt 0.750000 0.333333
vt 0.750000 0.000000
vt 0.670541 0.333333
vt 0.670541 0.000000
vt 0.588278 0.333333
vt 0.588278 0.000000
vt 0.500000 0.333333
vt 0.411722 0.333333
vt 0.500000 0.000000
vt 0.411722 0.000000
vt 0.329460 0.333333
vt 0.329460 0.000000
vt 0.250001 0.333333
vt 0.250001 0.000000
vt 0.250001 0.666667
vt 0.329460 0.666667
vt 0.329460 1.000000
vt 0.250001 1.000000
vt 0.829459 0.000000
vt 0.829459 0.333333
vt 0.329459 0.333333
vt 0.329459 0.000000
vt 0.250000 0.000000
vt 0.250000 0.333333
s 1
usemtl 材质.028
f 5/1/1 6/2/2 2/3/3 1/4/1
f 1/4/1 2/3/3 19/5/3 3/6/4
f 15/7/5 4/8/6 1/4/1 3/6/4
f 4/8/6 7/9/5 5/1/1 1/4/1
f 7/10/7 8/11/7 9/12/7 69/13/7 68/14/7 67/15/7 66/16/7 52/17/7 51/18/7 50/19/7 49/20/7 45/21/7 79/22/7 80/23/7 81/24/7 82/25/7 87/26/7 88/27/7 89/28/7 90/29/7 95/30/7 96/31/7 6/32/7 5/33/7
f 10/4/8 8/1/9 7/34/5 4/35/6
f 10/4/8 11/36/10 9/37/11 8/1/9
f 12/6/9 10/4/8 4/35/6 15/38/5
f 12/6/9 14/39/11 11/36/10 10/4/8
f 14/39/11 12/6/9 13/40/9 76/41/11
f 12/6/9 15/38/5 16/42/5 13/40/9
f 17/40/4 16/43/5 15/7/5 3/6/4
f 38/22/12 40/21/12 41/20/12 59/19/12 56/18/12 60/17/12 62/16/12 77/15/12 73/14/12 75/13/12 76/12/12 13/11/12 16/10/12 17/33/12 18/32/12 20/31/12 22/30/12 24/29/12 26/28/12 28/27/12 30/26/12 32/25/12 34/24/12 36/23/12
f 18/44/3 17/40/4 3/6/4 19/5/3
f 20/45/13 18/44/3 19/5/3 21/46/14
f 22/47/15 20/45/13 21/46/14 23/48/16
f 24/49/17 22/47/15 23/48/16 25/50/18
f 26/28/19 24/49/17 25/50/18 27/51/20
f 28/52/21 26/28/19 27/51/20 29/53/22
f 30/54/23 28/52/21 29/53/22 31/55/23
f 32/56/24 30/54/23 31/55/23 33/57/24
f 34/58/25 32/56/24 33/57/24 35/59/26
f 36/60/27 34/58/25 35/59/26 37/61/28
f 39/62/29 38/63/30 36/60/27 37/61/28
f 42/61/31 40/60/32 38/63/30 39/62/29
f 42/61/31 43/64/33 41/65/34 40/60/32
f 44/66/31 42/61/31 39/62/29 46/67/29
f 43/64/33 42/61/31 44/66/31 47/68/34
f 47/68/34 44/66/31 45/69/31 49/70/34
f 44/66/31 46/67/29 79/71/29 45/69/31
f 58/57/35 43/64/33 47/68/34 48/72/35
f 48/72/35 47/68/34 49/70/34 50/73/35
f 53/74/36 48/72/35 50/73/35 51/75/36
f 54/76/37 53/74/36 51/75/36 52/77/37
f 57/53/38 55/55/36 53/74/36 54/76/37
f 55/55/36 58/57/35 48/72/35 53/74/36
f 58/57/35 55/55/36 56/54/36 59/56/35
f 55/55/36 57/53/38 60/52/37 56/54/36
f 43/64/33 58/57/35 59/56/35 41/65/34
f 61/51/39 57/53/38 54/76/37 64/78/40
f 57/53/38 61/51/39 62/28/40 60/52/37
f 61/51/39 63/50/41 77/49/42 62/28/40
f 63/50/41 61/51/39 64/78/40 65/79/42
f 65/79/42 64/78/40 66/80/40 67/81/42
f 64/78/40 54/76/37 52/77/37 66/80/40
f 70/82/43 65/79/42 67/81/42 68/83/44
f 71/84/45 70/82/43 68/83/44 69/85/46
f 74/86/45 72/87/43 70/82/43 71/84/45
f 72/87/43 63/50/41 65/79/42 70/82/43
f 63/50/41 72/87/43 73/88/44 77/49/42
f 72/87/43 74/86/45 75/89/46 73/88/44
f 14/39/11 74/86/45 71/84/45 11/36/10
f 74/86/45 14/39/11 76/41/11 75/89/46
f 11/36/10 71/84/45 69/85/46 9/37/11
f 80/69/28 79/71/29 46/67/29 78/66/28
f 46/67/29 39/62/29 37/61/28 78/66/28
f 81/90/25 80/69/28 78/66/28 83/91/25
f 82/73/47 81/90/25 83/91/25 84/72/47
f 84/72/47 83/91/25 35/59/26 33/57/24
f 83/91/25 78/66/28 37/61/28 35/59/26
f 85/74/48 84/72/47 33/57/24 31/55/23
f 87/75/48 82/73/47 84/72/47 85/74/48
f 88/77/21 87/75/48 85/74/48 86/76/22
f 86/76/22 85/74/48 31/55/23 29/53/22
f 89/80/19 88/77/21 86/76/22 91/78/19
f 90/81/17 89/80/19 91/78/19 92/79/17
f 92/79/17 91/78/19 27/51/20 25/50/18
f 91/78/19 86/76/22 29/53/22 27/51/20
f 93/92/16 92/79/17 25/50/18 23/48/16
f 95/93/15 90/81/17 92/79/17 93/92/16
f 96/94/13 95/93/15 93/92/16 94/95/14
f 94/95/14 93/92/16 23/48/16 21/46/14
f 6/2/2 96/94/13 94/95/14 2/3/3
f 2/3/3 94/95/14 21/46/14 19/5/3

View File

@ -0,0 +1,223 @@
<mujoco model="b2">
<compiler angle="radian" meshdir="../meshes" autolimits="true"/>
<default>
<default class="b2">
<geom type="mesh"/>
<joint damping="1" armature="0.1"/>
<default class="visual">
<geom contype="0" conaffinity="0" group="2"/>
</default>
<default class="collision">
<geom group="3" mass="0" density="0"/>
</default>
<site size="0.001" rgba="0.5 0.5 0.5 0.3" group="4"/>
</default>
</default>
<asset>
<mesh name="base_link" file="base_link.obj"/>
<mesh name="logo_left" file="logo_left.obj"/>
<mesh name="logo_right" file="logo_right.obj"/>
<mesh name="unitree_ladar" file="unitree_ladar.obj"/>
<mesh name="f_dc_link" file="f_dc_link.obj"/>
<mesh name="r_dc_link" file="r_dc_link.obj"/>
<mesh name="fake_imu_link" file="fake_imu_link.STL"/>
<mesh name="fake_head_Link" file="fake_head_Link.STL"/>
<mesh name="fake_tail_link" file="fake_tail_link.STL"/>
<mesh name="FL_hip" file="FL_hip.obj"/>
<mesh name="FL_thigh" file="FL_thigh.obj"/>
<mesh name="FL_thigh_protect" file="FL_thigh_protect.obj"/>
<mesh name="FL_calf" file="FL_calf.obj"/>
<mesh name="FL_foot" file="FL_foot.obj"/>
<mesh name="FR_hip" file="FR_hip.obj"/>
<mesh name="FR_thigh" file="FR_thigh.obj"/>
<mesh name="FR_thigh_protect" file="FR_thigh_protect.obj"/>
<mesh name="FR_calf" file="FR_calf.obj"/>
<mesh name="FR_foot" file="FR_foot.obj"/>
<mesh name="RL_hip" file="RL_hip.obj"/>
<mesh name="RL_thigh" file="RL_thigh.obj"/>
<mesh name="RL_thigh_protect" file="RL_thigh_protect.obj"/>
<mesh name="RL_calf" file="RL_calf.obj"/>
<mesh name="RL_foot" file="RL_foot.obj"/>
<mesh name="RR_hip" file="RR_hip.obj"/>
<mesh name="RR_thigh" file="RR_thigh.obj"/>
<mesh name="RR_thigh_protect" file="RR_thigh_protect.obj"/>
<mesh name="RR_calf" file="RR_calf.obj"/>
<mesh name="RR_foot" file="RR_foot.obj"/>
<mesh name="f_oc_link" file="f_oc_link.obj"/>
<mesh name="r_oc_link" file="r_oc_link.obj"/>
</asset>
<worldbody>
<body name="base_link" pos="0 0 0.8" childclass="b2">
<inertial pos="0.0212868 0.0045819 0.0106169" quat="0.00178111 0.675412 -0.000262894 0.737438" mass="40.8426" diaginertia="1.73786 1.66448 0.343734"/>
<joint name="floating_base_joint" type="free"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="base_link"/>
<geom size="0.25 0.14 0.075" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="1 1 1 1" mesh="logo_left"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="1 1 1 1" mesh="logo_right"/>
<geom pos="0.34218 0 0.17851" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.15 0.15 0.15 1" mesh="unitree_ladar"/>
<geom size="0.076 0.08" pos="0.34218 0 0.15851" type="cylinder" rgba="0.15 0.15 0.15 1" class="collision"/>
<geom pos="0.841724 -4.57659e-06 0.130379" quat="0.00244632 3.13845e-06 0.999997 1.29099e-06" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0 0 0 1" mesh="f_dc_link"/>
<geom pos="-0.378319 0.000200109 -0.379902" quat="-1.30076e-06 -0.708662 5.35065e-07 0.705548" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0 0 0 1" mesh="r_dc_link"/>
<geom pos="0 -0.02341 0.04927" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0 0 0 1" mesh="fake_imu_link"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0 0 0 1" mesh="fake_head_Link"/>
<geom size="0.02 0.06 0.07" pos="0.41 0 0.005" type="box" rgba="0 0 0 1" class="collision"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0 0 0 1" mesh="fake_tail_link"/>
<geom size="0.0125 0.06 0.07" pos="-0.405 0 0.005" type="box" rgba="0 0 0 1" class="collision"/>
<geom pos="0.84158 -0.0134347 -0.0134347" quat="-3.89602e-06 1.29867e-06 0.707107 -0.707107" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0 0 0 1" mesh="f_oc_link"/>
<geom pos="-0.00451008 0.0252504 -0.0262476" quat="0.707107 -0.707107 -1.29867e-06 -1.29867e-06" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0 0 0 1" mesh="r_oc_link"/>
<site name="imu" pos="0 -0.02341 0.04927"/>
<body name="FL_hip" pos="0.3285 0.072 0">
<inertial pos="-0.00829923 -0.00998502 0.000235465" quat="0.525168 0.518964 0.477213 0.476595" mass="2.5294" diaginertia="0.00485541 0.00370618 0.00277182"/>
<joint name="FL_hip_joint" pos="0 0 0" axis="1 0 0" range="-0.87 0.87"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="FL_hip"/>
<geom size="0.07 0.025" pos="0 0.12 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.7 0.7 0.7 1" class="collision"/>
<body name="FL_thigh" pos="0 0.11973 0">
<inertial pos="-0.00418663 -0.0366068 -0.0432737" quat="0.884916 0.0880602 -0.00896728 0.457262" mass="7.4554" diaginertia="0.085057 0.0842843 0.0112538"/>
<joint name="FL_thigh_joint" pos="0 0 0" axis="0 1 0" range="-0.94 4.69"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="FL_thigh"/>
<geom size="0.16 0.02225 0.027" pos="-0.025 0 -0.16" quat="0.707388 0 0.706825 0" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.65 0.68 0.65 1" mesh="FL_thigh_protect"/>
<body name="FL_calf" pos="0 -8.6984e-05 -0.35">
<inertial pos="0.0096848 1.25758e-05 -0.158987" quat="0.70753 -0.00625821 -0.00634277 0.706627" mass="0.679123" diaginertia="0.0162494 0.0161173 0.000398115"/>
<joint name="FL_calf_joint" pos="0 0 0" axis="0 1 0" range="-2.82 -0.43"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="FL_calf"/>
<geom size="0.05 0.01225 0.009" pos="-0.002 0 -0.03" quat="0.825336 0 0.564642 0" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom size="0.05 0.01225 0.009" pos="0.022 0 -0.1" quat="0.780707 0 0.624897 0" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom size="0.075 0.01225 0.0075" pos="0.036 0 -0.225" quat="0.721382 0 0.692537 0" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom size="0.025 0.014 0.0175" pos="0.023 0 -0.31" quat="0.540302 0 0.841471 0" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom pos="0 8.6986e-05 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.15 0.15 0.15 1" mesh="FL_foot" friction="0.4 0.005 0.0001"/>
<geom size="0.032 0.025" pos="0 8.6986e-05 -0.35" quat="0.707388 0.706825 0 0" type="cylinder" rgba="0.15 0.15 0.15 1" class="collision" friction="0.4 0.005 0.0001"/>
</body>
</body>
</body>
<body name="FR_hip" pos="0.3285 -0.072 0">
<inertial pos="-0.00829923 0.00998502 0.000235465" quat="0.476595 0.477213 0.518964 0.525168" mass="2.5294" diaginertia="0.00485541 0.00370618 0.00277182"/>
<joint name="FR_hip_joint" pos="0 0 0" axis="1 0 0" range="-0.87 0.87"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="FR_hip"/>
<geom size="0.07 0.025" pos="0 -0.12 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.7 0.7 0.7 1" class="collision"/>
<body name="FR_thigh" pos="0 -0.11973 0">
<inertial pos="-0.00418663 0.0366068 -0.0432737" quat="0.457262 -0.00896728 0.0880602 0.884916" mass="7.4554" diaginertia="0.085057 0.0842843 0.0112538"/>
<joint name="FR_thigh_joint" pos="0 0 0" axis="0 1 0" range="-0.94 4.69"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="FR_thigh"/>
<geom size="0.125 0.014 0.02" pos="-0.03 0 -0.2" quat="0.707388 0 0.706825 0" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.65 0.68 0.65 1" mesh="FR_thigh_protect"/>
<body name="FR_calf" pos="0 8.6986e-05 -0.35">
<inertial pos="0.0096848 0 -0.158987" quat="0.707079 -0.00630052 -0.00630052 0.707079" mass="0.679123" diaginertia="0.0162494 0.0161173 0.000398115"/>
<joint name="FR_calf_joint" pos="0 0 0" axis="0 1 0" range="-2.82 -0.43"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="FR_calf"/>
<geom size="0.05 0.01225 0.009" pos="-0.002 0 -0.03" quat="0.825336 0 0.564642 0" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom size="0.05 0.01225 0.009" pos="0.022 0 -0.1" quat="0.780707 0 0.624897 0" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom size="0.075 0.01225 0.0075" pos="0.036 0 -0.225" quat="0.721382 0 0.692537 0" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom size="0.025 0.014 0.0175" pos="0.023 0 -0.31" quat="0.540302 0 0.841471 0" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.15 0.15 0.15 1" mesh="FR_foot" friction="0.4 0.005 0.0001"/>
<geom size="0.032 0.025" pos="0 0 -0.35" quat="0.707388 0.706825 0 0" type="cylinder" rgba="0.15 0.15 0.15 1" class="collision" friction="0.4 0.005 0.0001"/>
</body>
</body>
</body>
<body name="RL_hip" pos="-0.3285 0.072 0">
<inertial pos="0.00829923 -0.00998502 0.000235465" quat="0.477213 0.476595 0.525168 0.518964" mass="2.5294" diaginertia="0.00485541 0.00370618 0.00277182"/>
<joint name="RL_hip_joint" pos="0 0 0" axis="1 0 0" range="-0.87 0.87"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="RL_hip"/>
<geom size="0.07 0.025" pos="0 0.12 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.7 0.7 0.7 1" class="collision"/>
<body name="RL_thigh" pos="0 0.11973 0">
<inertial pos="-0.00418663 -0.0366068 -0.0432737" quat="0.884916 0.0880602 -0.00896728 0.457262" mass="7.4554" diaginertia="0.085057 0.0842843 0.0112538"/>
<joint name="RL_thigh_joint" pos="0 0 0" axis="0 1 0" range="-0.94 4.69"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="RL_thigh"/>
<geom size="0.125 0.014 0.02" pos="-0.03 0 -0.2" quat="0.707388 0 0.706825 0" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.65 0.68 0.65 1" mesh="RL_thigh_protect"/>
<body name="RL_calf" pos="0 -8.6984e-05 -0.35">
<inertial pos="0.0096848 1.25758e-05 -0.158987" quat="0.70753 -0.00625821 -0.00634277 0.706627" mass="0.679123" diaginertia="0.0162494 0.0161173 0.000398115"/>
<joint name="RL_calf_joint" pos="0 0 0" axis="0 1 0" range="-2.82 -0.43"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="RL_calf"/>
<geom size="0.05 0.01225 0.009" pos="-0.002 0 -0.03" quat="0.825336 0 0.564642 0" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom size="0.05 0.01225 0.009" pos="0.022 0 -0.1" quat="0.780707 0 0.624897 0" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom size="0.075 0.01225 0.0075" pos="0.036 0 -0.225" quat="0.721382 0 0.692537 0" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom size="0.025 0.014 0.0175" pos="0.023 0 -0.31" quat="0.540302 0 0.841471 0" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom pos="0 8.6986e-05 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.15 0.15 0.15 1" mesh="RL_foot" friction="0.4 0.005 0.0001"/>
<geom size="0.032 0.025" pos="0 8.6986e-05 -0.35" quat="0.707388 0.706825 0 0" type="cylinder" rgba="0.15 0.15 0.15 1" class="collision" friction="0.4 0.005 0.0001"/>
</body>
</body>
</body>
<body name="RR_hip" pos="-0.3285 -0.072 0">
<inertial pos="0.00829923 -0.00825992 0.000235465" quat="0.524846 0.53164 0.469132 0.470967" mass="2.5294" diaginertia="0.0048658 0.00378576 0.00284106"/>
<joint name="RR_hip_joint" pos="0 0 0" axis="1 0 0" range="-0.87 0.87"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="RR_hip"/>
<geom size="0.07 0.025" pos="0 -0.12 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.7 0.7 0.7 1" class="collision"/>
<body name="RR_thigh" pos="0 -0.11973 0">
<inertial pos="-0.00418663 0.0366068 -0.0432737" quat="0.457262 -0.00896728 0.0880602 0.884916" mass="7.4554" diaginertia="0.085057 0.0842843 0.0112538"/>
<joint name="RR_thigh_joint" pos="0 0 0" axis="0 1 0" range="-0.94 4.69"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="RR_thigh"/>
<geom size="0.125 0.014 0.02" pos="-0.03 0 -0.2" quat="0.707388 0 0.706825 0" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.65 0.68 0.65 1" mesh="RR_thigh_protect"/>
<body name="RR_calf" pos="0 8.6986e-05 -0.35">
<inertial pos="0.0096848 -1.25756e-05 -0.158987" quat="0.706627 -0.00634277 -0.00625821 0.70753" mass="0.679123" diaginertia="0.0162494 0.0161173 0.000398115"/>
<joint name="RR_calf_joint" pos="0 0 0" axis="0 1 0" range="-2.82 -0.43"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="RR_calf"/>
<geom size="0.05 0.01225 0.009" pos="-0.002 0 -0.03" quat="0.825336 0 0.564642 0" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom size="0.05 0.01225 0.009" pos="0.022 0 -0.1" quat="0.780707 0 0.624897 0" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom size="0.075 0.01225 0.0075" pos="0.036 0 -0.225" quat="0.721382 0 0.692537 0" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom size="0.025 0.014 0.0175" pos="0.023 0 -0.31" quat="0.540302 0 0.841471 0" type="box" rgba="0.7 0.7 0.7 1" class="collision"/>
<geom pos="0 -8.6984e-05 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.15 0.15 0.15 1" mesh="RR_foot" friction="0.4 0.005 0.0001"/>
<geom size="0.032 0.025" pos="0 -8.6984e-05 -0.35" quat="0.707388 0.706825 0 0" type="cylinder" rgba="0.15 0.15 0.15 1" class="collision" friction="0.4 0.005 0.0001"/>
</body>
</body>
</body>
</body>
</worldbody>
<actuator>
<motor class="b2" ctrlrange="-200 200" name="FR_hip" joint="FR_hip_joint"/>
<motor class="b2" ctrlrange="-200 200" name="FR_thigh" joint="FR_thigh_joint"/>
<motor class="b2" ctrlrange="-300 300" name="FR_calf" joint="FR_calf_joint"/>
<motor class="b2" ctrlrange="-200 200" name="FL_hip" joint="FL_hip_joint"/>
<motor class="b2" ctrlrange="-200 200" name="FL_thigh" joint="FL_thigh_joint"/>
<motor class="b2" ctrlrange="-300 300" name="FL_calf" joint="FL_calf_joint"/>
<motor class="b2" ctrlrange="-200 200" name="RR_hip" joint="RR_hip_joint"/>
<motor class="b2" ctrlrange="-200 200" name="RR_thigh" joint="RR_thigh_joint"/>
<motor class="b2" ctrlrange="-300 300" name="RR_calf" joint="RR_calf_joint"/>
<motor class="b2" ctrlrange="-200 200" name="RL_hip" joint="RL_hip_joint"/>
<motor class="b2" ctrlrange="-200 200" name="RL_thigh" joint="RL_thigh_joint"/>
<motor class="b2" ctrlrange="-300 300" name="RL_calf" joint="RL_calf_joint"/>
</actuator>
<sensor>
<jointpos name="FR_hip_pos" joint="FR_hip_joint" />
<jointpos name="FR_thigh_pos" joint="FR_thigh_joint" />
<jointpos name="FR_calf_pos" joint="FR_calf_joint" />
<jointpos name="FL_hip_pos" joint="FL_hip_joint" />
<jointpos name="FL_thigh_pos" joint="FL_thigh_joint" />
<jointpos name="FL_calf_pos" joint="FL_calf_joint" />
<jointpos name="RR_hip_pos" joint="RR_hip_joint" />
<jointpos name="RR_thigh_pos" joint="RR_thigh_joint" />
<jointpos name="RR_calf_pos" joint="RR_calf_joint" />
<jointpos name="RL_hip_pos" joint="RL_hip_joint" />
<jointpos name="RL_thigh_pos" joint="RL_thigh_joint" />
<jointpos name="RL_calf_pos" joint="RL_calf_joint" />
<jointvel name="FR_hip_vel" joint="FR_hip_joint" />
<jointvel name="FR_thigh_vel" joint="FR_thigh_joint" />
<jointvel name="FR_calf_vel" joint="FR_calf_joint" />
<jointvel name="FL_hip_vel" joint="FL_hip_joint" />
<jointvel name="FL_thigh_vel" joint="FL_thigh_joint" />
<jointvel name="FL_calf_vel" joint="FL_calf_joint" />
<jointvel name="RR_hip_vel" joint="RR_hip_joint" />
<jointvel name="RR_thigh_vel" joint="RR_thigh_joint" />
<jointvel name="RR_calf_vel" joint="RR_calf_joint" />
<jointvel name="RL_hip_vel" joint="RL_hip_joint" />
<jointvel name="RL_thigh_vel" joint="RL_thigh_joint" />
<jointvel name="RL_calf_vel" joint="RL_calf_joint" />
<framequat name="body_quat" objtype="site" objname="imu" />
<gyro name="body_gyro" site="imu" />
<accelerometer name="body_acc" site="imu" />
<framepos name="body_pos" objtype="site" objname="imu" />
</sensor>
<keyframe>
<key name="home" qpos="0 0 0.5 1 0 0 0 0 1.28 -2.84 0 1.28 -2.84 0 1.28 -2.84 0 1.28 -2.84"
ctrl="0 1.28 -2.84 0 1.28 -2.84 0 1.28 -2.84 0 1.28 -2.84"/>
</keyframe>
</mujoco>

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,23 @@
<mujoco model="b2 scene">
<include file="b2.xml"/>
<statistic center="0 0 0.1" extent="0.8"/>
<visual>
<headlight diffuse="0.6 0.6 0.6" ambient="0.3 0.3 0.3" specular="0 0 0"/>
<rgba haze="0.15 0.25 0.35 1"/>
<global azimuth="-130" elevation="-20"/>
</visual>
<asset>
<texture type="skybox" builtin="gradient" rgb1="0.3 0.5 0.7" rgb2="0 0 0" width="512" height="3072"/>
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3"
markrgb="0.8 0.8 0.8" width="300" height="300"/>
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
</asset>
<worldbody>
<light pos="0 0 1.5" dir="0 0 -1" directional="true"/>
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
</worldbody>
</mujoco>