add lidar for deep robotics lite3

This commit is contained in:
Huang Zhenbiao 2025-03-01 22:08:59 +08:00
parent 5e6a9d0b9c
commit 354e235fdf
22 changed files with 1295 additions and 726 deletions

View File

@ -128,6 +128,8 @@ def generate_launch_description():
executable="parameter_bridge",
arguments=[
"/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock",
"/odom@nav_msgs/msg/Odometry@gz.msgs.Odometry",
"/tf@tf2_msgs/msg/TFMessage@gz.msgs.Pose_V"
],
output="screen"
)

View File

@ -36,7 +36,7 @@ namespace ocs2::legged_robot {
void StateEstimateBase::updateContact() {
const size_t size = ctrl_component_.foot_force_state_interface_.size();
for (int i = 0; i < size; i++) {
contact_flag_[i] = ctrl_component_.foot_force_state_interface_[i].get().get_value() > 10.0;
contact_flag_[i] = ctrl_component_.foot_force_state_interface_[i].get().get_value() > 5.0;
}
}

View File

@ -59,4 +59,16 @@ ros2 launch lite3_description visualize.launch.py
```bash
source ~/ros2_ws/install/setup.bash
ros2 launch unitree_guide_controller gazebo.launch.py pkg_description:=lite3_description height:=0.43
```
```
* OCS2 Quadruped Controller
```bash
source ~/ros2_ws/install/setup.bash
ros2 launch ocs2_quadruped_controller gazebo.launch.py pkg_description:=lite3_description height:=0.43
```
### Gazebo Playground (ROS2 Jazzy)
* OCS2 Quadruped Controller
```bash
source ~/ros2_ws/install/setup.bash
ros2 launch gz_quadruped_playground gazebo.launch.py pkg_description:=lite3_description controller:=ocs2 world:=warehouse
```

View File

@ -10,12 +10,12 @@ controller_manager:
imu_sensor_broadcaster:
type: imu_sensor_broadcaster/IMUSensorBroadcaster
leg_pd_controller:
type: leg_pd_controller/LegPdController
unitree_guide_controller:
type: unitree_guide_controller/UnitreeGuideController
ocs2_quadruped_controller:
type: ocs2_quadruped_controller/Ocs2QuadrupedController
rl_quadruped_controller:
type: rl_quadruped_controller/LeggedGymController
@ -24,36 +24,70 @@ imu_sensor_broadcaster:
sensor_name: "imu_sensor"
frame_id: "imu_link"
leg_pd_controller:
ocs2_quadruped_controller:
ros__parameters:
update_rate: 1000 # Hz
update_rate: 200 # Hz
robot_pkg: "lite3_description"
default_kd: 2.0
joints:
- FR_HipX
- FR_HipY
- FR_Knee
- FL_HipX
- FL_HipY
- FL_Knee
- HR_HipX
- HR_HipY
- HR_Knee
- FR_HipX
- FR_HipY
- FR_Knee
- HL_HipX
- HL_HipY
- HL_Knee
- HR_HipX
- HR_HipY
- HR_Knee
command_interfaces:
- effort
state_interfaces:
- position
- velocity
- kp
- kd
state_interfaces:
- effort
- position
- velocity
feet:
- FL_FOOT
- FR_FOOT
- HL_FOOT
- HR_FOOT
imu_name: "imu_sensor"
base_name: "base"
imu_interfaces:
- orientation.w
- orientation.x
- orientation.y
- orientation.z
- angular_velocity.x
- angular_velocity.y
- angular_velocity.z
- linear_acceleration.x
- linear_acceleration.y
- linear_acceleration.z
# estimator_type: "odom"
foot_force_name: "foot_force"
foot_force_interfaces:
- FL_foot_force
- HL_foot_force
- FR_foot_force
- HR_foot_force
unitree_guide_controller:
ros__parameters:
update_rate: 200 # Hz
# stand_kp: 30.0
stand_kd: 1.0
command_prefix: "leg_pd_controller"
joints:
- FR_HipX
- FR_HipY

View File

@ -1,22 +1,22 @@
targetDisplacementVelocity 0.5;
targetRotationVelocity 1.57;
comHeight 0.39
comHeight 0.3;
defaultJointState
{
(0,0) 0.1 ; FL_HipX
(1,0) -0.732 ; FL_HipY
(2,0) 1.361 ; FL_Knee
(1,0) -0.985 ; FL_HipY
(2,0) 2.084 ; FL_Knee
(3,0) -0.1 ; FR_HipX
(4,0) -0.732 ; FR_HipY
(5,0) 1.361 ; FR_Knee
(4,0) -0.985 ; FR_HipY
(5,0) 2.084 ; FR_Knee
(6,0) 0.1 ; HL_HipX
(7,0) -0.732 ; HL_HipY
(8,0) 1.361 ; HL_Knee
(7,0) -0.985 ; HL_HipY
(8,0) 2.084 ; HL_Knee
(9,0) -0.1 ; HR_HipX
(10,0) -0.732 ; HR_HipY
(11,0) 1.361 ; HR_Knee
(10,0) -0.985 ; HR_HipY
(11,0) 2.084 ; HR_Knee
}
initialModeSchedule

View File

@ -154,24 +154,24 @@ initialState
;; Base Pose: [position, orientation] ;;
(6,0) 0.0 ; p_base_x
(7,0) 0.0 ; p_base_y
(8,0) 0.39 ; p_base_z
(8,0) 0.3 ; p_base_z
(9,0) 0.0 ; theta_base_z
(10,0) 0.0 ; theta_base_y
(11,0) 0.0 ; theta_base_x
;; Leg Joint Positions: [FL, HL, FR, HR] ;;
(12,0) 0.1 ; FL_HipX
(13,0) -0.732 ; FL_HipY
(14,0) 1.361 ; FL_Knee
(13,0) -0.985 ; FL_HipY
(14,0) 2.084 ; FL_Knee
(15,0) 0.1 ; HL_HipX
(16,0) -0.732 ; HL_HipY
(17,0) 1.361 ; HL_Knee
(16,0) -0.985 ; HL_HipY
(17,0) 2.084 ; HL_Knee
(18,0) -0.1 ; FR_HipX
(19,0) -0.732 ; FR_HipY
(20,0) 1.361 ; FR_Knee
(19,0) -0.985 ; FR_HipY
(20,0) 2.084 ; FR_Knee
(21,0) -0.1 ; HR_HipX
(22,0) -0.732 ; HR_HipY
(23,0) 1.361 ; HR_Knee
(22,0) -0.985 ; HR_HipY
(23,0) 2.084 ; HR_Knee
}
; standard state weight matrix
@ -180,12 +180,12 @@ Q
scaling 1e+0
;; Normalized Centroidal Momentum: [linear, angular] ;;
(0,0) 15.0 ; vcom_x
(1,1) 15.0 ; vcom_y
(2,2) 100.0 ; vcom_z
(3,3) 10.0 ; L_x / robotMass
(4,4) 30.0 ; L_y / robotMass
(5,5) 30.0 ; L_z / robotMass
(0,0) 10.0 ; vcom_x
(1,1) 10.0 ; vcom_y
(2,2) 80.0 ; vcom_z
(3,3) 8.0 ; L_x / robotMass
(4,4) 20.0 ; L_y / robotMass
(5,5) 20.0 ; L_z / robotMass
;; Base Pose: [position, orientation] ;;
(6,6) 1000.0 ; p_base_x
@ -295,8 +295,8 @@ frictionConeTask
swingLegTask
{
kp 350
kd 37
kp 300
kd 20
}
weight

View File

@ -1,451 +0,0 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="damping" value="0.1"/>
<xacro:property name="friction" value="0.1"/>
<xacro:include filename="$(find lite3_description)/xacro/imu_link.xacro"/>
<link name="base">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
</visual>
</link>
<joint name="floating_base" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="base"/>
<child link="TORSO"/>
</joint>
<link name="TORSO">
<visual>
<origin rpy="0 0 3.1416" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find lite3_description)/meshes/Lite3.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.35 0.184 0.08"/>
</geometry>
</collision>
</link>
<link name="INERTIA">
<inertial>
<origin xyz="0.004098 -0.000663 -0.002069"/>
<mass value="4.130"/>
<inertia ixx="0.016982120" ixy="2.1294E-05" ixz="6.0763E-05" iyy="0.030466501" iyz="1.7968E-05"
izz="0.042609956"/>
</inertial>
</link>
<joint name="Torso2Inertia" type="fixed">
<parent link="TORSO"/>
<child link="INERTIA"/>
</joint>
<link name="FL_HIP">
<inertial>
<origin xyz="-0.0047 -0.0091 -0.0018"/>
<mass value="0.428"/>
<inertia ixx="0.00014538" ixy="8.1579E-07" ixz="-1.264E-05" iyy="0.00024024" iyz="1.3443E-06" izz="0.00013038"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.05 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find lite3_description)/meshes/FL_HIP.dae"/>
</geometry>
</visual>
</link>
<joint name="FL_HipX" type="revolute">
<origin xyz="0.1745 0.062 0"/>
<parent link="TORSO"/>
<child link="FL_HIP"/>
<axis xyz="-1 0 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="-0.42" upper="0.42" effort="24" velocity="26"/>
</joint>
<link name="FL_THIGH">
<inertial>
<origin xyz="-0.00523 -0.0216 -0.0273"/>
<mass value="0.61"/>
<inertia ixx="0.001" ixy="-2.5E-06" ixz="-1.12E-04" iyy="0.00116" iyz="3.75E-07" izz="2.68E-04"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find lite3_description)/meshes/l_thigh.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.08"/>
<geometry>
<box size="0.02 0.02 0.16"/>
</geometry>
</collision>
</link>
<joint name="FL_HipY" type="revolute">
<origin xyz="0 0.0985 0"/>
<parent link="FL_HIP"/>
<child link="FL_THIGH"/>
<axis xyz="0 -1 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="-2.67" upper="0.314" effort="24" velocity="26"/>
</joint>
<link name="FL_SHANK">
<inertial>
<origin xyz="0.00585 -8.732E-07 -0.12"/>
<mass value="0.115"/>
<inertia ixx="6.68E-04" ixy="-1.24E-08" ixz="6.91E-06" iyy="6.86E-04" iyz="5.65E-09" izz="3.155E-05"/>
</inertial>
<visual>
<origin rpy="3.14 -1.42 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find lite3_description)/meshes/SHANK.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.09"/>
<geometry>
<box size="0.02 0.02 0.18"/>
</geometry>
</collision>
</link>
<joint name="FL_Knee" type="revolute">
<origin xyz="0 0 -0.20"/>
<parent link="FL_THIGH"/>
<child link="FL_SHANK"/>
<axis xyz="0 -1 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="0.6" upper="2.72" effort="36" velocity="17"/>
</joint>
<link name="FL_FOOT">
<inertial>
<mass value="1E-12"/>
<inertia ixx="1E-12" ixy="0" ixz="0" iyy="1E-12" iyz="0" izz="1E-12"/>
</inertial>
<collision>
<geometry>
<sphere radius="0.013"/>
</geometry>
</collision>
</link>
<joint name="FL_Ankle" type="fixed">
<origin xyz="0 0 -0.21"/>
<parent link="FL_SHANK"/>
<child link="FL_FOOT"/>
</joint>
<link name="FR_HIP">
<inertial>
<origin xyz="-0.0047 0.0091 -0.0018"/>
<mass value="0.428"/>
<inertia ixx="0.00014538" ixy="-8.1551E-07" ixz="-1.2639E-05" iyy="0.00024024" iyz="-1.3441E-06"
izz="0.00013038"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.05 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find lite3_description)/meshes/FR_HIP.dae"/>
</geometry>
</visual>
</link>
<joint name="FR_HipX" type="revolute">
<origin xyz="0.1745 -0.062 0"/>
<parent link="TORSO"/>
<child link="FR_HIP"/>
<axis xyz="-1 0 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="-0.42" upper="0.42" effort="24" velocity="26"/>
</joint>
<link name="FR_THIGH">
<inertial>
<origin xyz="-0.00523 0.0216 -0.0273"/>
<mass value="0.61"/>
<inertia ixx="0.001" ixy="2.5E-06" ixz="-1.12E-04" iyy="0.00116" iyz="-3.75E-07" izz="2.68E-04"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find lite3_description)/meshes/r_thigh.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.08"/>
<geometry>
<box size="0.02 0.02 0.16"/>
</geometry>
</collision>
</link>
<joint name="FR_HipY" type="revolute">
<origin xyz="0 -0.0985 0"/>
<parent link="FR_HIP"/>
<child link="FR_THIGH"/>
<axis xyz="0 -1 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="-2.67" upper="0.314" effort="24" velocity="26"/>
</joint>
<link name="FR_SHANK">
<inertial>
<origin xyz="0.00585 -8.732E-07 -0.12"/>
<mass value="0.115"/>
<inertia ixx="6.68E-04" ixy="-1.24E-08" ixz="6.91E-06" iyy="6.86E-04" iyz="5.65E-09" izz="3.155E-05"/>
</inertial>
<visual>
<origin rpy="3.14 -1.42 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find lite3_description)/meshes/SHANK.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.09"/>
<geometry>
<box size="0.02 0.02 0.18"/>
</geometry>
</collision>
</link>
<joint name="FR_Knee" type="revolute">
<origin xyz="0 0 -0.20"/>
<parent link="FR_THIGH"/>
<child link="FR_SHANK"/>
<axis xyz="0 -1 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="0.6" upper="2.72" effort="36" velocity="17"/>
</joint>
<link name="FR_FOOT">
<inertial>
<mass value="1E-12"/>
<inertia ixx="1E-12" ixy="0" ixz="0" iyy="1E-12" iyz="0" izz="1E-12"/>
</inertial>
<collision>
<geometry>
<sphere radius="0.013"/>
</geometry>
</collision>
</link>
<joint name="FR_Ankle" type="fixed">
<origin xyz="0 0 -0.21"/>
<parent link="FR_SHANK"/>
<child link="FR_FOOT"/>
</joint>
<link name="HL_HIP">
<inertial>
<origin xyz="0.0047 -0.0091 -0.0018"/>
<mass value="0.428"/>
<inertia ixx="0.00014538" ixy="-8.1585E-07" ixz="1.2639E-05" iyy="0.00024024" iyz="1.3444E-06" izz="0.00013038"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.05 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find lite3_description)/meshes/HL_HIP.dae"/>
</geometry>
</visual>
</link>
<joint name="HL_HipX" type="revolute">
<origin xyz="-0.1745 0.062 0"/>
<parent link="TORSO"/>
<child link="HL_HIP"/>
<axis xyz="-1 0 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="-0.42" upper="0.42" effort="24" velocity="26"/>
</joint>
<link name="HL_THIGH">
<inertial>
<origin xyz="-0.00523 -0.0216 -0.0273"/>
<mass value="0.61"/>
<inertia ixx="0.001" ixy="-2.5E-06" ixz="-1.12E-04" iyy="0.00116" iyz="3.75E-07" izz="2.68E-04"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find lite3_description)/meshes/l_thigh.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.08"/>
<geometry>
<box size="0.02 0.02 0.16"/>
</geometry>
</collision>
</link>
<joint name="HL_HipY" type="revolute">
<origin xyz="0 0.0985 0"/>
<parent link="HL_HIP"/>
<child link="HL_THIGH"/>
<axis xyz="0 -1 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="-2.67" upper="0.314" effort="24" velocity="26"/>
</joint>
<link name="HL_SHANK">
<inertial>
<origin xyz="0.00585 -8.732E-07 -0.12"/>
<mass value="0.115"/>
<inertia ixx="6.68E-04" ixy="-1.24E-08" ixz="6.91E-06" iyy="6.86E-04" iyz="5.65E-09" izz="3.155E-05"/>
</inertial>
<visual>
<origin rpy="3.14 -1.42 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find lite3_description)/meshes/SHANK.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.09"/>
<geometry>
<box size="0.02 0.02 0.18"/>
</geometry>
</collision>
</link>
<joint name="HL_Knee" type="revolute">
<origin xyz="0 0 -0.20"/>
<parent link="HL_THIGH"/>
<child link="HL_SHANK"/>
<axis xyz="0 -1 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="0.6" upper="2.72" effort="36" velocity="17"/>
</joint>
<link name="HL_FOOT">
<inertial>
<mass value="1E-12"/>
<inertia ixx="1E-12" ixy="0" ixz="0" iyy="1E-12" iyz="0" izz="1E-12"/>
</inertial>
<collision>
<geometry>
<sphere radius="0.013"/>
</geometry>
</collision>
</link>
<joint name="HL_Ankle" type="fixed">
<origin xyz="0 0 -0.21"/>
<parent link="HL_SHANK"/>
<child link="HL_FOOT"/>
</joint>
<link name="HR_HIP">
<inertial>
<origin xyz="0.0047 0.0091 -0.0018"/>
<mass value="0.428"/>
<inertia ixx="0.00014538" ixy="8.1545E-07" ixz="1.2639E-05" iyy="0.00024024" iyz="-1.344E-06" izz="0.00013038"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.05 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find lite3_description)/meshes/HR_HIP.dae"/>
</geometry>
</visual>
</link>
<joint name="HR_HipX" type="revolute">
<origin xyz="-0.1745 -0.062 0"/>
<parent link="TORSO"/>
<child link="HR_HIP"/>
<axis xyz="-1 0 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="-0.42" upper="0.42" effort="24" velocity="26"/>
</joint>
<link name="HR_THIGH">
<inertial>
<origin xyz="-0.00523 0.0216 -0.0273"/>
<mass value="0.61"/>
<inertia ixx="0.001" ixy="2.5E-06" ixz="-1.12E-04" iyy="0.00116" iyz="-3.75E-07" izz="2.68E-04"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find lite3_description)/meshes/r_thigh.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.08"/>
<geometry>
<box size="0.02 0.02 0.16"/>
</geometry>
</collision>
</link>
<joint name="HR_HipY" type="revolute">
<origin xyz="0 -0.0985 0"/>
<parent link="HR_HIP"/>
<child link="HR_THIGH"/>
<axis xyz="0 -1 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="-2.67" upper="0.314" effort="24" velocity="26"/>
</joint>
<link name="HR_SHANK">
<inertial>
<origin xyz="0.00585 -8.732E-07 -0.12"/>
<mass value="0.115"/>
<inertia ixx="6.68E-04" ixy="-1.24E-08" ixz="6.91E-06" iyy="6.86E-04" iyz="5.65E-09" izz="3.155E-05"/>
</inertial>
<visual>
<origin rpy="3.14 -1.42 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find lite3_description)/meshes/SHANK.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.09"/>
<geometry>
<box size="0.02 0.02 0.18"/>
</geometry>
</collision>
</link>
<joint name="HR_Knee" type="revolute">
<origin xyz="0 0 -0.20"/>
<parent link="HR_THIGH"/>
<child link="HR_SHANK"/>
<axis xyz="0 -1 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="0.6" upper="2.72" effort="36" velocity="17"/>
</joint>
<link name="HR_FOOT">
<inertial>
<mass value="1E-12"/>
<inertia ixx="1E-12" ixy="0" ixz="0" iyy="1E-12" iyz="0" izz="1E-12"/>
</inertial>
<collision>
<geometry>
<sphere radius="0.013"/>
</geometry>
</collision>
</link>
<joint name="HR_Ankle" type="fixed">
<origin xyz="0 0 -0.21"/>
<parent link="HR_SHANK"/>
<child link="HR_FOOT"/>
</joint>
</robot>

View File

@ -0,0 +1,41 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="damping" value="0.0"/>
<xacro:property name="friction" value="0.1"/>
<xacro:property name="thigh_offset" value="0.0955"/>
<xacro:property name="leg_offset_x" value="0.1745"/>
<xacro:property name="leg_offset_y" value="0.062"/>
<!-- hip (left front) -->
<xacro:property name="hip_mass" value="0.428"/>
<xacro:property name="hip_com_x" value="-0.0047"/>
<xacro:property name="hip_com_y" value="-0.0091"/>
<xacro:property name="hip_com_z" value="-0.0018"/>
<xacro:property name="hip_ixx" value="0.00014538"/>
<xacro:property name="hip_ixy" value="8.1579E-07"/>
<xacro:property name="hip_ixz" value="-1.264E-05"/>
<xacro:property name="hip_iyy" value="0.00024024"/>
<xacro:property name="hip_iyz" value="1.3443E-06"/>
<xacro:property name="hip_izz" value="0.00013038"/>
<!-- thigh -->
<xacro:property name="thigh_mass" value="0.61"/>
<xacro:property name="thigh_com_x" value="-0.00523"/>
<xacro:property name="thigh_com_y" value="-0.0216"/>
<xacro:property name="thigh_com_z" value="-0.0273"/>
<xacro:property name="thigh_ixx" value="0.001"/>
<xacro:property name="thigh_ixy" value="-2.5E-06"/>
<xacro:property name="thigh_ixz" value="-1.12E-04"/>
<xacro:property name="thigh_iyy" value="0.00116"/>
<xacro:property name="thigh_iyz" value="3.75E-07"/>
<xacro:property name="thigh_izz" value="2.68E-04"/>
<!-- foot -->
<xacro:property name="foot_mass" value="0.06"/>
<xacro:property name="foot_radius" value="0.013"/>
</robot>

View File

@ -1,90 +1,151 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find gz_quadruped_hardware)/xacro/foot_force_sensor.xacro"/>
<ros2_control name="GazeboSystem" type="system">
<hardware>
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
<plugin>gz_quadruped_hardware/GazeboSimSystem</plugin>
</hardware>
<joint name="FR_HipX">
<command_interface name="effort" initial_value="0.0"/>
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FR_HipY">
<command_interface name="effort" initial_value="0.0"/>
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FR_Knee">
<command_interface name="effort" initial_value="0.0"/>
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_HipX">
<command_interface name="effort" initial_value="0.0"/>
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_HipY">
<command_interface name="effort" initial_value="0.0"/>
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_Knee">
<command_interface name="effort" initial_value="0.0"/>
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HR_HipX">
<command_interface name="effort" initial_value="0.0"/>
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HR_HipY">
<command_interface name="effort" initial_value="0.0"/>
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HR_Knee">
<command_interface name="effort" initial_value="0.0"/>
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HL_HipX">
<command_interface name="effort" initial_value="0.0"/>
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HL_HipY">
<command_interface name="effort" initial_value="0.0"/>
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HL_Knee">
<command_interface name="effort" initial_value="0.0"/>
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
@ -102,15 +163,34 @@
<state_interface name="linear_acceleration.y"/>
<state_interface name="linear_acceleration.z"/>
</sensor>
<sensor name="foot_force">
<state_interface name="FR_foot_force"/>
<state_interface name="FL_foot_force"/>
<state_interface name="HR_foot_force"/>
<state_interface name="HL_foot_force"/>
</sensor>
</ros2_control>
<gazebo>
<plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
<plugin filename="gz_quadruped_hardware-system" name="gz_quadruped_hardware::GazeboSimQuadrupedPlugin">
<parameters>$(find lite3_description)/config/gazebo.yaml</parameters>
</plugin>
<plugin filename="gz-sim-imu-system"
name="gz::sim::systems::Imu">
</plugin>
<plugin filename="gz-sim-forcetorque-system" name="gz::sim::systems::ForceTorque"/>
<!-- <plugin filename="gz-sim-odometry-publisher-system"-->
<!-- name="gz::sim::systems::OdometryPublisher">-->
<!-- <odom_frame>odom</odom_frame>-->
<!-- <robot_base_frame>base</robot_base_frame>-->
<!-- <odom_publish_frequency>1000</odom_publish_frequency>-->
<!-- <odom_topic>odom</odom_topic>-->
<!-- <dimensions>3</dimensions>-->
<!-- <odom_covariance_topic>odom_with_covariance</odom_covariance_topic>-->
<!-- <tf_topic>tf</tf_topic>-->
<!-- </plugin>-->
</gazebo>
<gazebo reference="trunk">
@ -128,61 +208,82 @@
<imu>
<angular_velocity>
<x>
<!-- <noise type="gaussian">-->
<!-- <mean>0.0</mean>-->
<!-- <stddev>2e-4</stddev>-->
<!-- <bias_mean>0.0000075</bias_mean>-->
<!-- <bias_stddev>0.0000008</bias_stddev>-->
<!-- </noise>-->
<noise type="gaussian">
<mean>0.0</mean>
<stddev>2e-4</stddev>
<bias_mean>0.0000075</bias_mean>
<bias_stddev>0.0000008</bias_stddev>
</noise>
</x>
<y>
<!-- <noise type="gaussian">-->
<!-- <mean>0.0</mean>-->
<!-- <stddev>2e-4</stddev>-->
<!-- <bias_mean>0.0000075</bias_mean>-->
<!-- <bias_stddev>0.0000008</bias_stddev>-->
<!-- </noise>-->
<noise type="gaussian">
<mean>0.0</mean>
<stddev>2e-4</stddev>
<bias_mean>0.0000075</bias_mean>
<bias_stddev>0.0000008</bias_stddev>
</noise>
</y>
<z>
<!-- <noise type="gaussian">-->
<!-- <mean>0.0</mean>-->
<!-- <stddev>2e-4</stddev>-->
<!-- <bias_mean>0.0000075</bias_mean>-->
<!-- <bias_stddev>0.0000008</bias_stddev>-->
<!-- </noise>-->
<noise type="gaussian">
<mean>0.0</mean>
<stddev>2e-4</stddev>
<bias_mean>0.0000075</bias_mean>
<bias_stddev>0.0000008</bias_stddev>
</noise>
</z>
</angular_velocity>
<linear_acceleration>
<x>
<!-- <noise type="gaussian">-->
<!-- <mean>0.0</mean>-->
<!-- <stddev>1.7e-2</stddev>-->
<!-- <bias_mean>0.1</bias_mean>-->
<!-- <bias_stddev>0.001</bias_stddev>-->
<!-- </noise>-->
<noise type="gaussian">
<mean>0.0</mean>
<stddev>1.7e-2</stddev>
<bias_mean>0.1</bias_mean>
<bias_stddev>0.001</bias_stddev>
</noise>
</x>
<y>
<!-- <noise type="gaussian">-->
<!-- <mean>0.0</mean>-->
<!-- <stddev>1.7e-2</stddev>-->
<!-- <bias_mean>0.1</bias_mean>-->
<!-- <bias_stddev>0.001</bias_stddev>-->
<!-- </noise>-->
<noise type="gaussian">
<mean>0.0</mean>
<stddev>1.7e-2</stddev>
<bias_mean>0.1</bias_mean>
<bias_stddev>0.001</bias_stddev>
</noise>
</y>
<z>
<!-- <noise type="gaussian">-->
<!-- <mean>0.0</mean>-->
<!-- <stddev>1.7e-2</stddev>-->
<!-- <bias_mean>0.1</bias_mean>-->
<!-- <bias_stddev>0.001</bias_stddev>-->
<!-- </noise>-->
<noise type="gaussian">
<mean>0.0</mean>
<stddev>1.7e-2</stddev>
<bias_mean>0.1</bias_mean>
<bias_stddev>0.001</bias_stddev>
</noise>
</z>
</linear_acceleration>
</imu>
</sensor>
</gazebo>
<gazebo reference="imu_joint">
<disableFixedJointLumping>true</disableFixedJointLumping>
</gazebo>
<xacro:foot_force_sensor name="FL" suffix="Ankle"/>
<xacro:foot_force_sensor name="HL" suffix="Ankle"/>
<xacro:foot_force_sensor name="FR" suffix="Ankle"/>
<xacro:foot_force_sensor name="HR" suffix="Ankle"/>
<xacro:arg name="EXTERNAL_SENSORS" default="false"/>
<xacro:if value="$(arg EXTERNAL_SENSORS)">
<xacro:include filename="$(find gz_quadruped_playground)/models/D435/model.xacro"/>
<xacro:include filename="$(find gz_quadruped_playground)/models/Lidar3DV1/model.xacro"/>
<xacro:d435 camID="1" name="d435">
<origin rpy="0 0.1 0" xyz="0.23 0 0.06"/>
</xacro:d435>
<xacro:Lidar3D vertical="16" name="lslidar">
<origin rpy="0 0 0" xyz="0.163 0 0.058"/>
</xacro:Lidar3D>
</xacro:if>
</robot>

View File

@ -1,30 +0,0 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<joint name="imu_joint" type="fixed">
<parent link="TORSO"/>
<child link="imu_link"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<link name="imu_link">
<inertial>
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size=".001 .001 .001"/>
</geometry>
</collision>
</link>
</robot>

View File

@ -0,0 +1,164 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find lite3_description)/xacro/transmission.xacro"/>
<xacro:macro name="leg" params="name mirror mirror_dae front_hind front_hind_dae">
<joint name="${name}_HipX" 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="TORSO"/>
<child link="${name}_HIP"/>
<axis xyz="-1 0 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="-0.42" upper="0.42" effort="24" velocity="26"/>
</joint>
<link name="${name}_HIP">
<inertial>
<inertia ixx="0.00014538" ixy="8.1579E-07" ixz="-1.264E-05" iyy="0.00024024" iyz="1.3443E-06" izz="0.00013038"/>
<origin 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>
<visual>
<origin rpy="0 0 0" xyz="${-0.05*front_hind} 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find lite3_description)/meshes/${name}_HIP.dae"/>
</geometry>
</visual>
</link>
<joint name="${name}_HipY" type="revolute">
<origin 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 lower="-2.67" upper="0.314" effort="24" velocity="26"/>
</joint>
<link name="${name}_THIGH">
<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}"/>
<inertia ixx="0.001" ixy="-2.5E-06" ixz="-1.12E-04" iyy="0.00116" iyz="3.75E-07" izz="2.68E-04"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<geometry>
<xacro:if value="${mirror_dae == True}">
<mesh filename="file://$(find lite3_description)/meshes/l_thigh.dae"/>
</xacro:if>
<xacro:if value="${mirror_dae == False}">
<mesh filename="file://$(find lite3_description)/meshes/r_thigh.dae"/>
</xacro:if>
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.08"/>
<geometry>
<box size="0.02 0.02 0.16"/>
</geometry>
</collision>
</link>
<joint name="${name}_Knee" type="revolute">
<origin xyz="0 0 -0.20"/>
<parent link="${name}_THIGH"/>
<child link="${name}_SHANK"/>
<axis xyz="0 -1 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="0.6" upper="2.72" effort="36" velocity="17"/>
</joint>
<link name="${name}_SHANK">
<inertial>
<origin xyz="0.00585 -8.732E-07 -0.12"/>
<mass value="0.115"/>
<inertia ixx="6.68E-04" ixy="-1.24E-08" ixz="6.91E-06" iyy="6.86E-04" iyz="5.65E-09" izz="3.155E-05"/>
</inertial>
<visual>
<origin rpy="3.14 -1.42 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find lite3_description)/meshes/SHANK.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.09"/>
<geometry>
<box size="0.02 0.02 0.18"/>
</geometry>
</collision>
</link>
<joint name="${name}_Ankle" type="fixed">
<origin xyz="0 0 -0.21"/>
<parent link="${name}_SHANK"/>
<child link="${name}_FOOT"/>
</joint>
<link name="${name}_FOOT">
<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>
<collision>
<geometry>
<sphere radius="${foot_radius}"/>
</geometry>
</collision>
</link>
<gazebo reference="${name}_HIP">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="${name}_THIGH">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>0</self_collide>
<kp value="1000000.0"/>
<kd value="100.0"/>
</gazebo>
<gazebo reference="${name}_SHANK">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
</gazebo>
<gazebo reference="${name}_FOOT">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="100.0"/>
</gazebo>
<xacro:leg_transmission name="${name}"/>
</xacro:macro>
</robot>

View File

@ -2,8 +2,8 @@
<robot name="lite3" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find lite3_description)/xacro/body.xacro"/>
<xacro:include filename="$(find lite3_description)/xacro/transmission.xacro"/>
<xacro:include filename="$(find lite3_description)/xacro/const.xacro"/>
<xacro:include filename="$(find lite3_description)/xacro/leg.xacro"/>
<xacro:arg name="GAZEBO" default="false"/>
<xacro:arg name="CLASSIC" default="false"/>
@ -21,4 +21,70 @@
<xacro:include filename="$(find lite3_description)/xacro/ros2_control.xacro"/>
</xacro:unless>
<link name="base">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
</visual>
</link>
<joint name="floating_base" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="base"/>
<child link="TORSO"/>
</joint>
<link name="TORSO">
<visual>
<origin rpy="0 0 3.1416" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find lite3_description)/meshes/Lite3.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.35 0.184 0.08"/>
</geometry>
</collision>
<inertial>
<origin xyz="0.004098 -0.000663 -0.002069"/>
<mass value="4.130"/>
<inertia ixx="0.016982120" ixy="2.1294E-05" ixz="6.0763E-05" iyy="0.030466501" iyz="1.7968E-05"
izz="0.042609956"/>
</inertial>
</link>
<joint name="imu_joint" type="fixed">
<parent link="TORSO"/>
<child link="imu_link"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<link name="imu_link">
<inertial>
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size=".001 .001 .001"/>
</geometry>
</collision>
</link>
<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="HR" mirror="-1" mirror_dae="False" front_hind="-1" front_hind_dae="False"/>
<xacro:leg name="HL" mirror="1" mirror_dae="True" front_hind="-1" front_hind_dae="False"/>
</robot>

View File

@ -2,128 +2,34 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- FL transmissions -->
<transmission name="FL_HipX_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FL_HipX">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FL_HipX_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FL_HipY_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FL_HipY">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FL_HipY_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FL_Knee_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FL_Knee">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FL_Knee_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- FR transmissions -->
<transmission name="FR_HipX_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FR_HipX">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FR_HipX_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FR_HipY_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FR_HipY">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FR_HipY_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FR_Knee_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FR_Knee">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FR_Knee_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- HL transmissions -->
<transmission name="HL_HipX_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="HL_HipX">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="HL_HipX_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="HL_HipY_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="HL_HipY">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="HL_HipY_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="HL_Knee_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="HL_Knee">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="HL_Knee_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- HR transmissions -->
<transmission name="HR_HipX_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="HR_HipX">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="HR_HipX_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="HR_HipY_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="HR_HipY">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="HR_HipY_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="HR_Knee_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="HR_Knee">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="HR_Knee_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<xacro:macro name="leg_transmission" params="name">
<transmission name="${name}_HipX_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_HipX">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_HipX_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="{name}_HipY_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="{name}_HipY">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="{name}_HipY_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="{name}_Knee_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="{name}_Knee">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="{name}_Knee_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>
</robot>

View File

@ -61,6 +61,11 @@ ros2 launch go2_description visualize.launch.py
source ~/ros2_ws/install/setup.bash
ros2 launch unitree_guide_controller gazebo.launch.py
```
* OCS2 Quadruped Controller
```bash
source ~/ros2_ws/install/setup.bash
ros2 launch ocs2_quadruped_controller gazebo.launch.py
```
* RL Quadruped Controller
```bash
source ~/ros2_ws/install/setup.bash

View File

@ -51,7 +51,7 @@
<!-- joint limits -->
<xacro:property name="damping" value="0.0"/>
<xacro:property name="friction" value="0.0"/>
<xacro:property name="friction" value="0.01"/>
<xacro:property name="hip_position_max" value="1.0472"/>
<xacro:property name="hip_position_min" value="-1.0472"/>
<xacro:property name="hip_velocity_max" value="30.1"/>

View File

@ -169,16 +169,6 @@
name="gz::sim::systems::Imu">
</plugin>
<plugin filename="gz-sim-forcetorque-system" name="gz::sim::systems::ForceTorque"/>
<plugin filename="gz-sim-odometry-publisher-system"
name="gz::sim::systems::OdometryPublisher">
<odom_frame>odom</odom_frame>
<robot_base_frame>base</robot_base_frame>
<odom_publish_frequency>1000</odom_publish_frequency>
<odom_topic>odom</odom_topic>
<dimensions>3</dimensions>
<odom_covariance_topic>odom_with_covariance</odom_covariance_topic>
<tf_topic>tf</tf_topic>
</plugin>
</gazebo>
<gazebo reference="trunk">
@ -254,10 +244,10 @@
<disableFixedJointLumping>true</disableFixedJointLumping>
</gazebo>
<xacro:foot_force_sensor name="FL"/>
<xacro:foot_force_sensor name="RL"/>
<xacro:foot_force_sensor name="FR"/>
<xacro:foot_force_sensor name="RR"/>
<xacro:foot_force_sensor name="FL" suffix="foot_fixed"/>
<xacro:foot_force_sensor name="RL" suffix="foot_fixed"/>
<xacro:foot_force_sensor name="FR" suffix="foot_fixed"/>
<xacro:foot_force_sensor name="RR" suffix="foot_fixed"/>
<xacro:arg name="EXTERNAL_SENSORS" default="false"/>
<xacro:if value="$(arg EXTERNAL_SENSORS)">

View File

@ -1,8 +1,8 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="foot_force_sensor" params="name">
<gazebo reference="${name}_foot_fixed">
<xacro:macro name="foot_force_sensor" params="name suffix">
<gazebo reference="${name}_${suffix}">
<!-- Enable feedback for this joint -->
<provide_feedback>true</provide_feedback>
<!-- Prevent ros2_control from lumping this fixed joint with others -->

View File

@ -0,0 +1,599 @@
Panels:
- Class: rviz_common/Displays
Help Height: 270
Name: Displays
Property Tree Widget:
Expanded:
- /TF1/Frames1
- /Target Trajectories1/Target Feet Trajectories1/Marker1
- /Target Trajectories1/Target Feet Trajectories1/Marker2
- /Target Trajectories1/Target Feet Trajectories1/Marker3
- /Target Trajectories1/Target Feet Trajectories1/Marker4
- /Target Trajectories1/Target Base Trajectory1
- /PointCloud22
Splitter Ratio: 0.5
Tree Height: 638
- Class: rviz_common/Selection
Name: Selection
- Class: rviz_common/Tool Properties
Expanded:
- /2D Pose Estimate1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz_common/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz_common/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: PointCloud2
- Class: rviz_common/Displays
Help Height: 138
Name: Displays
Property Tree Widget:
Expanded: ~
Splitter Ratio: 0.8294117450714111
Tree Height: 268
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz_default_plugins/Grid
Color: 0; 0; 0
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: 100
Reference Frame: odom
Value: true
- Alpha: 0.800000011920929
Class: rviz_default_plugins/RobotModel
Collision Enabled: false
Description File: ""
Description Source: Topic
Description Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /robot_description
Enabled: true
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
FL_calf:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
FL_foot:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
FL_hip:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
FL_thigh:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
FR_calf:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
FR_foot:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
FR_hip:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
FR_thigh:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Link Tree Style: Links in Alphabetic Order
RL_calf:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
RL_foot:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
RL_hip:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
RL_thigh:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
RR_calf:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
RR_foot:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
RR_hip:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
RR_thigh:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
base:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera_d435:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
front_camera:
Alpha: 1
Show Axes: false
Show Trail: false
imu_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
lidar:
Alpha: 1
Show Axes: false
Show Trail: false
trunk:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Mass Properties:
Inertia: false
Mass: false
Name: RobotModel
TF Prefix: ""
Update Interval: 0
Value: true
Visual Enabled: true
- Class: rviz_default_plugins/TF
Enabled: true
Filter (blacklist): ""
Filter (whitelist): ""
Frame Timeout: 15
Frames:
All Enabled: false
FL_calf:
Value: true
FL_foot:
Value: true
FL_hip:
Value: true
FL_thigh:
Value: true
FR_calf:
Value: true
FR_foot:
Value: true
FR_hip:
Value: true
FR_thigh:
Value: true
RL_calf:
Value: true
RL_foot:
Value: true
RL_hip:
Value: true
RL_thigh:
Value: true
RR_calf:
Value: true
RR_foot:
Value: true
RR_hip:
Value: true
RR_thigh:
Value: true
base:
Value: false
camera_d435:
Value: true
front_camera:
Value: true
imu_link:
Value: false
lidar:
Value: true
odom:
Value: true
trunk:
Value: true
Marker Scale: 1
Name: TF
Show Arrows: true
Show Axes: false
Show Names: false
Tree:
odom:
base:
trunk:
FL_hip:
FL_thigh:
FL_calf:
FL_foot:
{}
FR_hip:
FR_thigh:
FR_calf:
FR_foot:
{}
RL_hip:
RL_thigh:
RL_calf:
RL_foot:
{}
RR_hip:
RR_thigh:
RR_calf:
RR_foot:
{}
camera_d435:
{}
front_camera:
{}
imu_link:
{}
lidar:
{}
Update Interval: 0
Value: true
- Class: rviz_default_plugins/MarkerArray
Enabled: true
Name: Optimized State Trajectory
Namespaces:
CoM Trajectory: true
EE Trajectories: true
Future footholds: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /legged_robot/optimizedStateTrajectory
Value: true
- Class: rviz_default_plugins/MarkerArray
Enabled: true
Name: Current State
Namespaces:
Center of Pressure: true
EE Forces: true
EE Positions: true
Support Polygon: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /legged_robot/currentState
Value: true
- Class: rviz_common/Group
Displays:
- Class: rviz_common/Group
Displays:
- Class: rviz_default_plugins/Marker
Enabled: true
Name: Marker
Namespaces:
{}
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /legged_robot/desiredFeetTrajectory/LF
Value: true
- Class: rviz_default_plugins/Marker
Enabled: true
Name: Marker
Namespaces:
{}
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /legged_robot/desiredFeetTrajectory/LH
Value: true
- Class: rviz_default_plugins/Marker
Enabled: true
Name: Marker
Namespaces:
{}
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /legged_robot/desiredFeetTrajectory/RF
Value: true
- Class: rviz_default_plugins/Marker
Enabled: true
Name: Marker
Namespaces:
{}
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /legged_robot/desiredFeetTrajectory/RH
Value: true
Enabled: false
Name: Target Feet Trajectories
- Class: rviz_default_plugins/Marker
Enabled: true
Name: Target Base Trajectory
Namespaces:
"": true
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /legged_robot/desiredBaseTrajectory
Value: true
Enabled: true
Name: Target Trajectories
- Alpha: 1
Autocompute Intensity Bounds: true
Class: grid_map_rviz_plugin/GridMap
Color: 200; 200; 200
Color Layer: elevation
Color Transformer: GridMapLayer
Enabled: true
Height Layer: elevation
Height Transformer: GridMapLayer
History Length: 1
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 10
Min Color: 0; 0; 0
Min Intensity: 0
Name: GridMap
Show Grid Lines: true
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /raisim_heightmap
Use Rainbow: true
Value: true
- Class: rviz_default_plugins/Image
Enabled: true
Max Value: 1
Median window: 5
Min Value: 0
Name: Image
Normalize Range: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /camera/image
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rviz_default_plugins/PointCloud2
Color: 255; 255; 255
Color Transformer: RGB8
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 4096
Min Color: 0; 0; 0
Min Intensity: 0
Name: PointCloud2
Position Transformer: XYZ
Selectable: true
Size (Pixels): 3
Size (m): 0.009999999776482582
Style: Flat Squares
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /rgbd_d435/points
Use Fixed Frame: true
Use rainbow: true
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rviz_default_plugins/PointCloud2
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 0
Min Color: 0; 0; 0
Min Intensity: 0
Name: PointCloud2
Position Transformer: XYZ
Selectable: true
Size (Pixels): 3
Size (m): 0.009999999776482582
Style: Flat Squares
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /scan/points
Use Fixed Frame: true
Use rainbow: true
Value: true
Enabled: true
Global Options:
Background Color: 198; 198; 198
Fixed Frame: odom
Frame Rate: 30
Name: root
Tools:
- Class: rviz_default_plugins/Interact
Hide Inactive Objects: true
- Class: rviz_default_plugins/Select
- Class: rviz_default_plugins/Measure
Line color: 128; 128; 0
- Class: rviz_default_plugins/SetInitialPose
Covariance x: 0.25
Covariance y: 0.25
Covariance yaw: 0.06853891909122467
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /initialpose
- Class: rviz_default_plugins/SetGoal
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /move_base_simple/goal
- Class: rviz_default_plugins/PublishPoint
Single click: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /clicked_point
Transformation:
Current:
Class: rviz_default_plugins/TF
Value: true
Views:
Current:
Class: rviz_default_plugins/Orbit
Distance: 2.071281671524048
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: -1.0683034658432007
Y: -0.7991123795509338
Z: 0.4058437943458557
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.18039782345294952
Target Frame: trunk
Value: Orbit (rviz_default_plugins)
Yaw: 3.5117714405059814
Saved:
- Class: rviz_default_plugins/Orbit
Distance: 2.071281671524048
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: -1.0683034658432007
Y: -0.7991123795509338
Z: 0.4058437943458557
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Orbit
Near Clip Distance: 0.009999999776482582
Pitch: 0.46039777994155884
Target Frame: trunk
Value: Orbit (rviz_default_plugins)
Yaw: 3.326773166656494
Window Geometry:
Displays:
collapsed: false
Height: 1182
Hide Left Dock: true
Hide Right Dock: false
Image:
collapsed: false
QMainWindow State: 000000ff00000000fd0000000400000000000001f4000003fefc020000000cfb0000001200530065006c0065006300740069006f006e000000006e000000b0000000b200fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073000000006e00000477000000b200fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730000000070000003fe0000018600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006101000001be000001900000000000000000fb000000100044006900730070006c006100790073000000006e000002470000018600fffffffb0000000a0049006d0061006700650000000070000002990000002800fffffffb0000000a0049006d0061006700650100000395000000d90000000000000000000000010000015d000003fefc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000070000003fe0000013800fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000006400000003efc0100000002fb0000000800540069006d00650000000000000006400000047a00fffffffb0000000800540069006d006501000000000000045000000000000000000000070f000003fe00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1807
X: 2248
Y: 914

View File

@ -51,15 +51,6 @@ def launch_setup(context, *args, **kwargs):
],
)
rviz_config_file = os.path.join(get_package_share_directory('gz_quadruped_playground'), "config", "rviz.rviz")
rviz = Node(
package='rviz2',
executable='rviz2',
name='rviz',
output='screen',
arguments=["-d", rviz_config_file]
)
# Controllers
controller = context.launch_configurations['controller']
if controller == 'ocs2':
@ -68,12 +59,22 @@ def launch_setup(context, *args, **kwargs):
'launch',
'ocs2.launch.py'])])
)
rviz_config_file = os.path.join(get_package_share_directory('gz_quadruped_playground'), "config", "ocs2.rviz")
else:
controller_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource([PathJoinSubstitution([FindPackageShare('gz_quadruped_playground'),
'launch',
'unitree_guide.launch.py'])])
)
rviz_config_file = os.path.join(get_package_share_directory('gz_quadruped_playground'), "config", "rviz.rviz")
rviz = Node(
package='rviz2',
executable='rviz2',
name='rviz',
output='screen',
arguments=["-d", rviz_config_file]
)
return [
rviz,

View File

@ -4,7 +4,7 @@
<xacro:macro name="d435" params="camID name *origin">
<joint name="camera_joint_${name}" type="fixed">
<xacro:insert_block name="origin"/>
<parent link="trunk"/>
<parent link="base"/>
<child link="camera_${name}"/>
</joint>
@ -77,7 +77,7 @@
<optical_frame_id>camera_${name}</optical_frame_id>
</camera>
<always_on>true</always_on>
<update_rate>15</update_rate>
<update_rate>30</update_rate>
<visualize>true</visualize>
<topic>rgbd_${name}</topic>
<plugin

View File

@ -0,0 +1,60 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="Lidar3D" params="vertical name *origin">
<joint name="lidar_joint_${name}" type="fixed">
<xacro:insert_block name="origin"/>
<parent link="base"/>
<child link="lidar_${name}"/>
</joint>
<link name="lidar_${name}">
<collision>
<origin xyz="0 0 0.03585" rpy="0 0 0"/>
<geometry>
<box size=".001 .001 .001"/>
</geometry>
</collision>
<inertial>
<mass value="0.83"/>
<inertia ixx="9.108e-05" ixy="0" ixz="0" iyy="2.51e-06" iyz="0" izz="8.931e-05"/>
<origin xyz="0 0 0.03585" rpy="0 0 0"/>
</inertial>
<visual>
<geometry>
<mesh filename="file://$(find gz_quadruped_playground)/models/Lidar3DV1/meshes/lidar_3d_v1.dae" scale="1 1 1"/>
</geometry>
</visual>
</link>
<gazebo reference="lidar_${name}">
<sensor name='${name}' type='gpu_lidar'>
<topic>scan</topic>
<update_rate>10</update_rate>
<gz_frame_id>lidar_${name}</gz_frame_id>
<lidar>
<scan>
<horizontal>
<samples>640</samples>
<resolution>1</resolution>
<min_angle>0</min_angle>
<max_angle>6.28</max_angle>
</horizontal>
<vertical>
<samples>${vertical}</samples>
<resolution>1</resolution>
<min_angle>-0.261799</min_angle>
<max_angle>0.261799</max_angle>
</vertical>
</scan>
<range>
<min>0.5</min>
<max>10.0</max>
<resolution>0.01</resolution>
</range>
</lidar>
<always_on>true</always_on>
<visualize>true</visualize>
</sensor>
</gazebo>
</xacro:macro>
</robot>

View File

@ -0,0 +1,69 @@
<?xml version="1.0" encoding="UTF-8"?>
<sdf version='1.9'>
<world name='simple_baylands'>
<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="gz-sim-sensors-system"
name="gz::sim::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
<plugin
filename="gz-sim-physics-system"
name="gz::sim::systems::Physics">
</plugin>
<plugin
filename="gz-sim-user-commands-system"
name="gz::sim::systems::UserCommands">
</plugin>
<plugin
filename="gz-sim-scene-broadcaster-system"
name="gz::sim::systems::SceneBroadcaster">
</plugin>
<atmosphere type='adiabatic'/>
<scene>
<ambient>0.8 0.5 1</ambient>
<grid>false</grid>
<sky>
<clouds>true</clouds>
</sky>
<shadows>1</shadows>
</scene>
<light name='sunUTC' type='directional'>
<pose>0 0 500 0 -0 0</pose>
<cast_shadows>false</cast_shadows>
<intensity>1</intensity>
<direction>0.001 0.625 -0.78</direction>
<diffuse>0.904 0.904 0.904 1</diffuse>
<specular>0.271 0.271 0.271 1</specular>
<attenuation>
<range>2000</range>
<linear>0</linear>
<constant>1</constant>
<quadratic>0</quadratic>
</attenuation>
</light>
<include>
<uri>
https://fuel.gazebosim.org/1.0/saurav/models/simple_baylands
</uri>
<name>park</name>
<pose>248 200 -1 0 0 -0.45</pose>
</include>
<include>
<uri>
https://fuel.gazebosim.org/1.0/OpenRobotics/models/Coast Water
</uri>
<pose relative_to="park">0 0 -2 0 0 0</pose>
</include>
<spherical_coordinates>
<surface_model>EARTH_WGS84</surface_model>
<world_frame_orientation>ENU</world_frame_orientation>
<latitude_deg>37.412173071650805</latitude_deg>
<longitude_deg>-121.998878727967</longitude_deg>
<elevation>38</elevation>
</spherical_coordinates>
</world>
</sdf>