add more support for gazebo classic simulationn

This commit is contained in:
Huang Zhenbiao 2024-10-24 15:05:26 +08:00
parent a6080328e0
commit 834ba68d4b
46 changed files with 3574 additions and 1961 deletions

View File

@ -10,13 +10,10 @@ from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare from launch_ros.substitutions import FindPackageShare
from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.launch_description_sources import PythonLaunchDescriptionSource
package_description = "go2_description"
def launch_setup(context, *args, **kwargs): def launch_setup(context, *args, **kwargs):
package_description = context.launch_configurations['pkg_description'] package_description = context.launch_configurations['pkg_description']
init_height = context.launch_configurations['height']
pkg_path = os.path.join(get_package_share_directory(package_description)) pkg_path = os.path.join(get_package_share_directory(package_description))
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro') xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
@ -42,7 +39,7 @@ def launch_setup(context, *args, **kwargs):
spawn_entity = Node( spawn_entity = Node(
package="gazebo_ros", package="gazebo_ros",
executable="spawn_entity.py", executable="spawn_entity.py",
arguments=["-topic", "robot_description", "-entity", "robot", "-z", "0.5"], arguments=["-topic", "robot_description", "-entity", "robot", "-z", init_height],
output="screen", output="screen",
) )
@ -109,7 +106,14 @@ def generate_launch_description():
description='package for robot description' description='package for robot description'
) )
height = DeclareLaunchArgument(
'height',
default_value='0.5',
description='Init height in simulation'
)
return LaunchDescription([ return LaunchDescription([
pkg_description, pkg_description,
height,
OpaqueFunction(function=launch_setup), OpaqueFunction(function=launch_setup),
]) ])

View File

@ -45,7 +45,15 @@ ros2 launch lite3_description visualize.launch.py
ros2 launch rl_quadruped_controller mujoco.launch.py pkg_description:=lite3_description model_folder:=legged_gym ros2 launch rl_quadruped_controller mujoco.launch.py pkg_description:=lite3_description model_folder:=legged_gym
``` ```
### Gazebo Simulator ### Gazebo Classic 11 (ROS2 Humble)
* Unitree Guide Controller
```bash
source ~/ros2_ws/install/setup.bash
ros2 launch unitree_guide_controller gazebo_classic.launch.py pkg_description:=lite3_description
```
### Gazebo Harmonic (ROS2 Jazzy)
* Unitree Guide Controller * Unitree Guide Controller
```bash ```bash

View File

@ -1,7 +1,7 @@
# Controller Manager configuration # Controller Manager configuration
controller_manager: controller_manager:
ros__parameters: ros__parameters:
update_rate: 2000 # Hz update_rate: 1000 # Hz
# Define the available controllers # Define the available controllers
joint_state_broadcaster: joint_state_broadcaster:
@ -26,6 +26,7 @@ imu_sensor_broadcaster:
leg_pd_controller: leg_pd_controller:
ros__parameters: ros__parameters:
update_rate: 1000 # Hz
joints: joints:
- FR_HipX - FR_HipX
- FR_HipY - FR_HipY
@ -50,6 +51,8 @@ leg_pd_controller:
unitree_guide_controller: unitree_guide_controller:
ros__parameters: ros__parameters:
update_rate: 200 # Hz update_rate: 200 # Hz
# stand_kp: 30.0
stand_kd: 1.0
command_prefix: "leg_pd_controller" command_prefix: "leg_pd_controller"
joints: joints:
- FR_HipX - FR_HipX

View File

@ -2,6 +2,9 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"> <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"/> <xacro:include filename="$(find lite3_description)/xacro/imu_link.xacro"/>
<link name="base"> <link name="base">
@ -66,6 +69,7 @@
<parent link="TORSO"/> <parent link="TORSO"/>
<child link="FL_HIP"/> <child link="FL_HIP"/>
<axis xyz="-1 0 0"/> <axis xyz="-1 0 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="-0.42" upper="0.42" effort="24" velocity="26"/> <limit lower="-0.42" upper="0.42" effort="24" velocity="26"/>
</joint> </joint>
@ -94,6 +98,7 @@
<parent link="FL_HIP"/> <parent link="FL_HIP"/>
<child link="FL_THIGH"/> <child link="FL_THIGH"/>
<axis xyz="0 -1 0"/> <axis xyz="0 -1 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="-2.67" upper="0.314" effort="24" velocity="26"/> <limit lower="-2.67" upper="0.314" effort="24" velocity="26"/>
</joint> </joint>
@ -122,6 +127,7 @@
<parent link="FL_THIGH"/> <parent link="FL_THIGH"/>
<child link="FL_SHANK"/> <child link="FL_SHANK"/>
<axis xyz="0 -1 0"/> <axis xyz="0 -1 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="0.6" upper="2.72" effort="36" velocity="17"/> <limit lower="0.6" upper="2.72" effort="36" velocity="17"/>
</joint> </joint>
@ -163,6 +169,7 @@
<parent link="TORSO"/> <parent link="TORSO"/>
<child link="FR_HIP"/> <child link="FR_HIP"/>
<axis xyz="-1 0 0"/> <axis xyz="-1 0 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="-0.42" upper="0.42" effort="24" velocity="26"/> <limit lower="-0.42" upper="0.42" effort="24" velocity="26"/>
</joint> </joint>
@ -191,6 +198,7 @@
<parent link="FR_HIP"/> <parent link="FR_HIP"/>
<child link="FR_THIGH"/> <child link="FR_THIGH"/>
<axis xyz="0 -1 0"/> <axis xyz="0 -1 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="-2.67" upper="0.314" effort="24" velocity="26"/> <limit lower="-2.67" upper="0.314" effort="24" velocity="26"/>
</joint> </joint>
@ -219,6 +227,7 @@
<parent link="FR_THIGH"/> <parent link="FR_THIGH"/>
<child link="FR_SHANK"/> <child link="FR_SHANK"/>
<axis xyz="0 -1 0"/> <axis xyz="0 -1 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="0.6" upper="2.72" effort="36" velocity="17"/> <limit lower="0.6" upper="2.72" effort="36" velocity="17"/>
</joint> </joint>
@ -259,6 +268,7 @@
<parent link="TORSO"/> <parent link="TORSO"/>
<child link="HL_HIP"/> <child link="HL_HIP"/>
<axis xyz="-1 0 0"/> <axis xyz="-1 0 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="-0.42" upper="0.42" effort="24" velocity="26"/> <limit lower="-0.42" upper="0.42" effort="24" velocity="26"/>
</joint> </joint>
@ -287,6 +297,7 @@
<parent link="HL_HIP"/> <parent link="HL_HIP"/>
<child link="HL_THIGH"/> <child link="HL_THIGH"/>
<axis xyz="0 -1 0"/> <axis xyz="0 -1 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="-2.67" upper="0.314" effort="24" velocity="26"/> <limit lower="-2.67" upper="0.314" effort="24" velocity="26"/>
</joint> </joint>
@ -315,6 +326,7 @@
<parent link="HL_THIGH"/> <parent link="HL_THIGH"/>
<child link="HL_SHANK"/> <child link="HL_SHANK"/>
<axis xyz="0 -1 0"/> <axis xyz="0 -1 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="0.6" upper="2.72" effort="36" velocity="17"/> <limit lower="0.6" upper="2.72" effort="36" velocity="17"/>
</joint> </joint>
@ -355,6 +367,7 @@
<parent link="TORSO"/> <parent link="TORSO"/>
<child link="HR_HIP"/> <child link="HR_HIP"/>
<axis xyz="-1 0 0"/> <axis xyz="-1 0 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="-0.42" upper="0.42" effort="24" velocity="26"/> <limit lower="-0.42" upper="0.42" effort="24" velocity="26"/>
</joint> </joint>
@ -383,6 +396,7 @@
<parent link="HR_HIP"/> <parent link="HR_HIP"/>
<child link="HR_THIGH"/> <child link="HR_THIGH"/>
<axis xyz="0 -1 0"/> <axis xyz="0 -1 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="-2.67" upper="0.314" effort="24" velocity="26"/> <limit lower="-2.67" upper="0.314" effort="24" velocity="26"/>
</joint> </joint>
@ -411,6 +425,7 @@
<parent link="HR_THIGH"/> <parent link="HR_THIGH"/>
<child link="HR_SHANK"/> <child link="HR_SHANK"/>
<axis xyz="0 -1 0"/> <axis xyz="0 -1 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit lower="0.6" upper="2.72" effort="36" velocity="17"/> <limit lower="0.6" upper="2.72" effort="36" velocity="17"/>
</joint> </joint>

View File

@ -117,13 +117,6 @@
<mu1>0.6</mu1> <mu1>0.6</mu1>
<mu2>0.6</mu2> <mu2>0.6</mu2>
<self_collide>1</self_collide> <self_collide>1</self_collide>
<visual>
<material>
<ambient>.05 .05 .05 1.0</ambient>
<diffuse>.05 .05 .05 1.0</diffuse>
<specular>.05 .05 .05 1.0</specular>
</material>
</visual>
</gazebo> </gazebo>
<gazebo reference="imu_link"> <gazebo reference="imu_link">

View File

@ -0,0 +1,238 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<ros2_control name="GazeboSystem" type="system">
<hardware>
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</hardware>
<joint name="FR_HipX">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FR_HipY">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FR_Knee">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_HipX">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_HipY">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_Knee">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HR_HipX">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HR_HipY">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HR_Knee">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HL_HipX">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HL_HipY">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HL_Knee">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<sensor name="imu_sensor">
<state_interface name="orientation.x"/>
<state_interface name="orientation.y"/>
<state_interface name="orientation.z"/>
<state_interface name="orientation.w"/>
<state_interface name="angular_velocity.x"/>
<state_interface name="angular_velocity.y"/>
<state_interface name="angular_velocity.z"/>
<state_interface name="linear_acceleration.x"/>
<state_interface name="linear_acceleration.y"/>
<state_interface name="linear_acceleration.z"/>
</sensor>
</ros2_control>
<gazebo>
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
<parameters>$(find lite3_description)/config/gazebo.yaml</parameters>
</plugin>
</gazebo>
<gazebo reference="trunk">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
</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>
<gazebo reference="TORSO">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="FL_HIP">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="FL_THIGH">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="FL_SHANK">
<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>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="FR_HIP">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="FR_THIGH">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="FR_SHANK">
<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>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="HL_HIP">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="HL_THIGH">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="HL_SHANK">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
</gazebo>
<gazebo reference="HL_FOOT">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="HR_HIP">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="HR_THIGH">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="HR_SHANK">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
</gazebo>
<gazebo reference="HR_FOOT">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
</robot>

View File

@ -6,8 +6,16 @@
<xacro:include filename="$(find lite3_description)/xacro/transmission.xacro"/> <xacro:include filename="$(find lite3_description)/xacro/transmission.xacro"/>
<xacro:arg name="GAZEBO" default="false"/> <xacro:arg name="GAZEBO" default="false"/>
<xacro:arg name="CLASSIC" default="false"/>
<xacro:if value="$(arg GAZEBO)"> <xacro:if value="$(arg GAZEBO)">
<xacro:if value="$(arg CLASSIC)">
<xacro:include filename="$(find lite3_description)/xacro/gazebo_classic.xacro"/>
</xacro:if>
<xacro:unless value="$(arg CLASSIC)">
<xacro:include filename="$(find lite3_description)/xacro/gazebo.xacro"/> <xacro:include filename="$(find lite3_description)/xacro/gazebo.xacro"/>
</xacro:unless>
</xacro:if> </xacro:if>
<xacro:unless value="$(arg GAZEBO)"> <xacro:unless value="$(arg GAZEBO)">
<xacro:include filename="$(find lite3_description)/xacro/ros2_control.xacro"/> <xacro:include filename="$(find lite3_description)/xacro/ros2_control.xacro"/>

View File

@ -35,7 +35,15 @@ ros2 launch x30_description visualize.launch.py
ros2 launch ocs2_quadruped_controller mujoco.launch.py pkg_description:=x30_description ros2 launch ocs2_quadruped_controller mujoco.launch.py pkg_description:=x30_description
``` ```
### Gazebo Simulator ### Gazebo Classic 11 (ROS2 Humble)
* Unitree Guide Controller
```bash
source ~/ros2_ws/install/setup.bash
ros2 launch unitree_guide_controller gazebo_classic.launch.py pkg_description:=x30_description height:=0.64
```
### Gazebo Harmonic (ROS2 Jazzy)
* Unitree Guide Controller * Unitree Guide Controller
```bash ```bash
source ~/ros2_ws/install/setup.bash source ~/ros2_ws/install/setup.bash

View File

@ -1,7 +1,7 @@
# Controller Manager configuration # Controller Manager configuration
controller_manager: controller_manager:
ros__parameters: ros__parameters:
update_rate: 2000 # Hz update_rate: 1000 # Hz
# Define the available controllers # Define the available controllers
joint_state_broadcaster: joint_state_broadcaster:
@ -26,6 +26,7 @@ imu_sensor_broadcaster:
leg_pd_controller: leg_pd_controller:
ros__parameters: ros__parameters:
update_rate: 1000 # Hz
joints: joints:
- FR_HipX - FR_HipX
- FR_HipY - FR_HipY
@ -65,6 +66,37 @@ unitree_guide_controller:
- HL_HipY - HL_HipY
- HL_Knee - HL_Knee
stand_kp: 300.0
stand_kd: 10.0
down_pos:
- 0.0
- -1.22
- 2.61
- 0.0
- -1.22
- 2.61
- 0.0
- -1.22
- 2.61
- 0.0
- -1.22
- 2.61
stand_pos:
- 0.0
- -0.732
- 1.361
- 0.0
- -0.732
- 1.361
- 0.0
- -0.732
- 1.361
- 0.0
- -0.732
- 1.361
command_interfaces: command_interfaces:
- effort - effort
- position - position

View File

@ -0,0 +1,246 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<ros2_control name="GazeboSystem" type="system">
<hardware>
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</hardware>
<joint name="FR_HipX">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FR_HipY">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FR_Knee">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_HipX">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_HipY">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_Knee">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HR_HipX">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HR_HipY">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HR_Knee">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HL_HipX">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HL_HipY">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HL_Knee">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<sensor name="imu_sensor">
<state_interface name="orientation.x"/>
<state_interface name="orientation.y"/>
<state_interface name="orientation.z"/>
<state_interface name="orientation.w"/>
<state_interface name="angular_velocity.x"/>
<state_interface name="angular_velocity.y"/>
<state_interface name="angular_velocity.z"/>
<state_interface name="linear_acceleration.x"/>
<state_interface name="linear_acceleration.y"/>
<state_interface name="linear_acceleration.z"/>
</sensor>
</ros2_control>
<gazebo>
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
<parameters>$(find x30_description)/config/gazebo.yaml</parameters>
</plugin>
</gazebo>
<gazebo reference="trunk">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
</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>
<gazebo reference="TORSO">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<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>
<kp value="1000000.0"/>
<kd value="1.0"/>
<material>Gazebo/Grey</material>
</gazebo>
<gazebo reference="FL_SHANK">
<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>
<kp value="1000000.0"/>
<kd value="100.0"/>
</gazebo>
<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>
<kp value="1000000.0"/>
<kd value="1.0"/>
<material>Gazebo/Grey</material>
</gazebo>
<gazebo reference="FR_SHANK">
<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>
<kp value="1000000.0"/>
<kd value="100.0"/>
</gazebo>
<gazebo reference="HL_HIP">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<material>Gazebo/DarkGrey</material>
</gazebo>
<gazebo reference="HL_THIGH">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
<material>Gazebo/Grey</material>
</gazebo>
<gazebo reference="HL_SHANK">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
</gazebo>
<gazebo reference="HL_FOOT">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="100.0"/>
</gazebo>
<gazebo reference="HR_HIP">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<material>Gazebo/DarkGrey</material>
</gazebo>
<gazebo reference="HR_THIGH">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
<material>Gazebo/Grey</material>
</gazebo>
<gazebo reference="HR_SHANK">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
</gazebo>
<gazebo reference="HR_FOOT">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="100.0"/>
</gazebo>
</robot>

View File

@ -7,8 +7,16 @@
<xacro:include filename="$(find x30_description)/xacro/transmission.xacro"/> <xacro:include filename="$(find x30_description)/xacro/transmission.xacro"/>
<xacro:arg name="GAZEBO" default="false"/> <xacro:arg name="GAZEBO" default="false"/>
<xacro:arg name="CLASSIC" default="false"/>
<xacro:if value="$(arg GAZEBO)"> <xacro:if value="$(arg GAZEBO)">
<xacro:if value="$(arg CLASSIC)">
<xacro:include filename="$(find x30_description)/xacro/gazebo_classic.xacro"/>
</xacro:if>
<xacro:unless value="$(arg CLASSIC)">
<xacro:include filename="$(find x30_description)/xacro/gazebo.xacro"/> <xacro:include filename="$(find x30_description)/xacro/gazebo.xacro"/>
</xacro:unless>
</xacro:if> </xacro:if>
<xacro:unless value="$(arg GAZEBO)"> <xacro:unless value="$(arg GAZEBO)">
<xacro:include filename="$(find x30_description)/xacro/ros2_control.xacro"/> <xacro:include filename="$(find x30_description)/xacro/ros2_control.xacro"/>

View File

@ -40,7 +40,15 @@ ros2 launch aliengo_description visualize.launch.py
ros2 launch ocs2_quadruped_controller mujoco.launch.py pkg_description:=aliengo_description ros2 launch ocs2_quadruped_controller mujoco.launch.py pkg_description:=aliengo_description
``` ```
### Gazebo Simulator ### Gazebo Classic 11 (ROS2 Humble)
* Unitree Guide Controller
```bash
source ~/ros2_ws/install/setup.bash
ros2 launch unitree_guide_controller gazebo_classic.launch.py pkg_description:=aliengo_description height:=0.535
```
### Gazebo Harmonic (ROS2 Jazzy)
* Unitree Guide Controller * Unitree Guide Controller
```bash ```bash

View File

@ -1,7 +1,7 @@
# Controller Manager configuration # Controller Manager configuration
controller_manager: controller_manager:
ros__parameters: ros__parameters:
update_rate: 2000 # Hz update_rate: 1000 # Hz
# Define the available controllers # Define the available controllers
joint_state_broadcaster: joint_state_broadcaster:
@ -26,6 +26,7 @@ imu_sensor_broadcaster:
leg_pd_controller: leg_pd_controller:
ros__parameters: ros__parameters:
update_rate: 1000 # Hz
joints: joints:
- FR_hip_joint - FR_hip_joint
- FR_thigh_joint - FR_thigh_joint

View File

@ -0,0 +1,238 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<ros2_control name="GazeboSystem" type="system">
<hardware>
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</hardware>
<joint name="FR_hip_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FR_thigh_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FR_calf_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_hip_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_thigh_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_calf_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RR_hip_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RR_thigh_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RR_calf_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RL_hip_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RL_thigh_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RL_calf_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<sensor name="imu_sensor">
<state_interface name="orientation.x"/>
<state_interface name="orientation.y"/>
<state_interface name="orientation.z"/>
<state_interface name="orientation.w"/>
<state_interface name="angular_velocity.x"/>
<state_interface name="angular_velocity.y"/>
<state_interface name="angular_velocity.z"/>
<state_interface name="linear_acceleration.x"/>
<state_interface name="linear_acceleration.y"/>
<state_interface name="linear_acceleration.z"/>
</sensor>
</ros2_control>
<gazebo>
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
<parameters>$(find aliengo_description)/config/gazebo.yaml</parameters>
</plugin>
</gazebo>
<gazebo reference="trunk">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
</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>
<!-- FL leg -->
<gazebo reference="FL_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="FL_thigh">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<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>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<!-- FR leg -->
<gazebo reference="FR_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="FR_thigh">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<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>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<!-- RL leg -->
<gazebo reference="RL_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="RL_thigh">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<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>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<!-- RR leg -->
<gazebo reference="RR_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="RR_thigh">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<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>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
</robot>

View File

@ -4,16 +4,22 @@
<xacro:arg name="DEBUG" default="false"/> <xacro:arg name="DEBUG" default="false"/>
<xacro:arg name="GAZEBO" default="false"/> <xacro:arg name="GAZEBO" default="false"/>
<xacro:arg name="CLASSIC" default="false"/>
<xacro:include filename="$(find aliengo_description)/xacro/const.xacro"/> <xacro:include filename="$(find aliengo_description)/xacro/const.xacro"/>
<xacro:include filename="$(find aliengo_description)/xacro/materials.xacro"/> <xacro:include filename="$(find aliengo_description)/xacro/materials.xacro"/>
<xacro:include filename="$(find aliengo_description)/xacro/leg.xacro"/> <xacro:include filename="$(find aliengo_description)/xacro/leg.xacro"/>
<xacro:if value="$(arg GAZEBO)"> <xacro:if value="$(arg GAZEBO)">
<xacro:include filename="$(find go2_description)/xacro/gazebo.xacro"/> <xacro:if value="$(arg CLASSIC)">
<xacro:include filename="$(find aliengo_description)/xacro/gazebo_classic.xacro"/>
</xacro:if>
<xacro:unless value="$(arg CLASSIC)">
<xacro:include filename="$(find aliengo_description)/xacro/gazebo.xacro"/>
</xacro:unless>
</xacro:if> </xacro:if>
<xacro:unless value="$(arg GAZEBO)"> <xacro:unless value="$(arg GAZEBO)">
<xacro:include filename="$(find go2_description)/xacro/ros2_control.xacro"/> <xacro:include filename="$(find aliengo_description)/xacro/ros2_control.xacro"/>
</xacro:unless> </xacro:unless>

View File

@ -35,7 +35,15 @@ ros2 launch b2_description visualize.launch.py
ros2 launch ocs2_quadruped_controller mujoco.launch.py pkg_description:=b2_description ros2 launch ocs2_quadruped_controller mujoco.launch.py pkg_description:=b2_description
``` ```
### Gazebo Simulator ### Gazebo Classic 11 (ROS2 Humble)
* Unitree Guide Controller
```bash
source ~/ros2_ws/install/setup.bash
ros2 launch unitree_guide_controller gazebo_classic.launch.py pkg_description:=b2_description height:=0.68
```
### Gazebo Harmonic (ROS2 Jazzy)
* Unitree Guide Controller * Unitree Guide Controller
```bash ```bash

View File

@ -1,7 +1,7 @@
# Controller Manager configuration # Controller Manager configuration
controller_manager: controller_manager:
ros__parameters: ros__parameters:
update_rate: 2000 # Hz update_rate: 1000 # Hz
# Define the available controllers # Define the available controllers
joint_state_broadcaster: joint_state_broadcaster:
@ -26,6 +26,7 @@ imu_sensor_broadcaster:
leg_pd_controller: leg_pd_controller:
ros__parameters: ros__parameters:
update_rate: 1000 # Hz
joints: joints:
- FR_hip_joint - FR_hip_joint
- FR_thigh_joint - FR_thigh_joint
@ -50,6 +51,9 @@ leg_pd_controller:
unitree_guide_controller: unitree_guide_controller:
ros__parameters: ros__parameters:
command_prefix: "leg_pd_controller" command_prefix: "leg_pd_controller"
update_rate: 500 # Hz
stand_kp: 500.0
stand_kd: 40.0
joints: joints:
- FR_hip_joint - FR_hip_joint
- FR_thigh_joint - FR_thigh_joint

View File

@ -57,8 +57,8 @@
<!-- joint limits --> <!-- joint limits -->
<xacro:property name="damping" value="0"/> <xacro:property name="damping" value="0.1"/>
<xacro:property name="friction" value="0"/> <xacro:property name="friction" value="0.1"/>
<xacro:property name="hip_position_max" value="0.87"/> <xacro:property name="hip_position_max" value="0.87"/>
<xacro:property name="hip_position_min" value="-0.87"/> <xacro:property name="hip_position_min" value="-0.87"/>
<xacro:property name="hip_velocity_max" value="23"/> <xacro:property name="hip_velocity_max" value="23"/>

View File

@ -0,0 +1,237 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<ros2_control name="GazeboSystem" type="system">
<hardware>
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</hardware>
<joint name="FR_hip_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FR_thigh_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FR_calf_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_hip_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_thigh_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_calf_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RR_hip_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RR_thigh_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RR_calf_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RL_hip_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RL_thigh_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RL_calf_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<sensor name="imu_sensor">
<state_interface name="orientation.x"/>
<state_interface name="orientation.y"/>
<state_interface name="orientation.z"/>
<state_interface name="orientation.w"/>
<state_interface name="angular_velocity.x"/>
<state_interface name="angular_velocity.y"/>
<state_interface name="angular_velocity.z"/>
<state_interface name="linear_acceleration.x"/>
<state_interface name="linear_acceleration.y"/>
<state_interface name="linear_acceleration.z"/>
</sensor>
</ros2_control>
<gazebo>
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
<parameters>$(find b2_description)/config/gazebo.yaml</parameters>
</plugin>
</gazebo>
<gazebo reference="trunk">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
</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>
<!-- FL leg -->
<gazebo reference="FL_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="FL_thigh">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<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>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<!-- FR leg -->
<gazebo reference="FR_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="FR_thigh">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<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>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<!-- RL leg -->
<gazebo reference="RL_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="RL_thigh">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<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>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<!-- RR leg -->
<gazebo reference="RR_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="RR_thigh">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<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>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
</robot>

View File

@ -4,13 +4,19 @@
<xacro:arg name="DEBUG" default="false"/> <xacro:arg name="DEBUG" default="false"/>
<xacro:arg name="GAZEBO" default="false"/> <xacro:arg name="GAZEBO" default="false"/>
<xacro:arg name="CLASSIC" default="false"/>
<xacro:include filename="$(find b2_description)/xacro/const.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/materials.xacro"/>
<xacro:include filename="$(find b2_description)/xacro/leg.xacro"/> <xacro:include filename="$(find b2_description)/xacro/leg.xacro"/>
<xacro:if value="$(arg GAZEBO)"> <xacro:if value="$(arg GAZEBO)">
<xacro:if value="$(arg CLASSIC)">
<xacro:include filename="$(find b2_description)/xacro/gazebo_classic.xacro"/>
</xacro:if>
<xacro:unless value="$(arg CLASSIC)">
<xacro:include filename="$(find b2_description)/xacro/gazebo.xacro"/> <xacro:include filename="$(find b2_description)/xacro/gazebo.xacro"/>
</xacro:unless>
</xacro:if> </xacro:if>
<xacro:unless value="$(arg GAZEBO)"> <xacro:unless value="$(arg GAZEBO)">
<xacro:include filename="$(find b2_description)/xacro/ros2_control.xacro"/> <xacro:include filename="$(find b2_description)/xacro/ros2_control.xacro"/>

View File

@ -35,7 +35,15 @@ ros2 launch go1_description visualize.launch.py
ros2 launch ocs2_quadruped_controller mujoco.launch.py pkg_description:=go1_description ros2 launch ocs2_quadruped_controller mujoco.launch.py pkg_description:=go1_description
``` ```
### Gazebo Simulator ### Gazebo Classic 11 (ROS2 Humble)
* Unitree Guide Controller
```bash
source ~/ros2_ws/install/setup.bash
ros2 launch unitree_guide_controller gazebo_classic.launch.py pkg_description:=go1_description
```
### Gazebo Harmonic (ROS2 Jazzy)
* Unitree Guide Controller * Unitree Guide Controller
```bash ```bash

View File

@ -1,7 +1,7 @@
# Controller Manager configuration # Controller Manager configuration
controller_manager: controller_manager:
ros__parameters: ros__parameters:
update_rate: 2000 # Hz update_rate: 1000 # Hz
# Define the available controllers # Define the available controllers
joint_state_broadcaster: joint_state_broadcaster:
@ -26,6 +26,7 @@ imu_sensor_broadcaster:
leg_pd_controller: leg_pd_controller:
ros__parameters: ros__parameters:
update_rate: 1000 # Hz
joints: joints:
- FR_hip_joint - FR_hip_joint
- FR_thigh_joint - FR_thigh_joint
@ -49,6 +50,7 @@ leg_pd_controller:
unitree_guide_controller: unitree_guide_controller:
ros__parameters: ros__parameters:
update_rate: 200 # Hz
command_prefix: "leg_pd_controller" command_prefix: "leg_pd_controller"
joints: joints:
- FR_hip_joint - FR_hip_joint

View File

@ -56,8 +56,8 @@
<xacro:property name="calf_rotor_offset_z" value="0.0"/> <xacro:property name="calf_rotor_offset_z" value="0.0"/>
<!-- joint limits --> <!-- joint limits -->
<xacro:property name="damping" value="0.0"/> <xacro:property name="damping" value="0.1"/>
<xacro:property name="friction" value="0.0"/> <xacro:property name="friction" value="0.1"/>
<xacro:property name="hip_position_max" value="0.863"/> <xacro:property name="hip_position_max" value="0.863"/>
<xacro:property name="hip_position_min" value="-0.863"/> <xacro:property name="hip_position_min" value="-0.863"/>
<xacro:property name="hip_velocity_max" value="30.1"/> <xacro:property name="hip_velocity_max" value="30.1"/>

View File

@ -0,0 +1,254 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<ros2_control name="GazeboSystem" type="system">
<hardware>
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</hardware>
<joint name="FR_hip_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FR_thigh_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FR_calf_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_hip_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_thigh_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_calf_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RR_hip_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RR_thigh_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RR_calf_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RL_hip_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RL_thigh_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RL_calf_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<sensor name="imu_sensor">
<state_interface name="orientation.x"/>
<state_interface name="orientation.y"/>
<state_interface name="orientation.z"/>
<state_interface name="orientation.w"/>
<state_interface name="angular_velocity.x"/>
<state_interface name="angular_velocity.y"/>
<state_interface name="angular_velocity.z"/>
<state_interface name="linear_acceleration.x"/>
<state_interface name="linear_acceleration.y"/>
<state_interface name="linear_acceleration.z"/>
</sensor>
</ros2_control>
<gazebo>
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
<parameters>$(find go1_description)/config/gazebo.yaml</parameters>
</plugin>
</gazebo>
<gazebo reference="trunk">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<material>Gazebo/Grey</material>
</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>
<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/Grey</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>
<material>Gazebo/DarkGrey</material>
</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/Grey</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>
<material>Gazebo/DarkGrey</material>
</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/Grey</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>
<material>Gazebo/DarkGrey</material>
</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/Grey</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>
<material>Gazebo/DarkGrey</material>
</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

@ -257,14 +257,14 @@
<gazebo reference="{name}_thigh"> <gazebo reference="{name}_thigh">
<mu1>0.2</mu1> <mu1>0.2</mu1>
<mu2>0.2</mu2> <mu2>0.2</mu2>
<self_collide>1</self_collide> <self_collide>0</self_collide>
<kp value="1000000.0"/> <kp value="1000000.0"/>
<kd value="1.0"/> <kd value="1.0"/>
</gazebo> </gazebo>
<gazebo reference="{name}_calf"> <gazebo reference="${name}_calf">
<mu1>0.2</mu1> <mu1>0.6</mu1>
<mu2>0.2</mu2> <mu2>0.6</mu2>
<self_collide>1</self_collide> <self_collide>1</self_collide>
</gazebo> </gazebo>

View File

@ -4,6 +4,7 @@
<xacro:arg name="DEBUG" default="false"/> <xacro:arg name="DEBUG" default="false"/>
<xacro:arg name="GAZEBO" default="false"/> <xacro:arg name="GAZEBO" default="false"/>
<xacro:arg name="CLASSIC" default="false"/>
<xacro:include filename="$(find go1_description)/xacro/const.xacro"/> <xacro:include filename="$(find go1_description)/xacro/const.xacro"/>
<xacro:include filename="$(find go1_description)/xacro/materials.xacro"/> <xacro:include filename="$(find go1_description)/xacro/materials.xacro"/>
@ -13,7 +14,12 @@
<xacro:include filename="$(find go1_description)/xacro/ultraSound.xacro"/> <xacro:include filename="$(find go1_description)/xacro/ultraSound.xacro"/>
<xacro:if value="$(arg GAZEBO)"> <xacro:if value="$(arg GAZEBO)">
<xacro:if value="$(arg CLASSIC)">
<xacro:include filename="$(find go1_description)/xacro/gazebo_classic.xacro"/>
</xacro:if>
<xacro:unless value="$(arg CLASSIC)">
<xacro:include filename="$(find go1_description)/xacro/gazebo.xacro"/> <xacro:include filename="$(find go1_description)/xacro/gazebo.xacro"/>
</xacro:unless>
</xacro:if> </xacro:if>
<xacro:unless value="$(arg GAZEBO)"> <xacro:unless value="$(arg GAZEBO)">
<xacro:include filename="$(find go1_description)/xacro/ros2_control.xacro"/> <xacro:include filename="$(find go1_description)/xacro/ros2_control.xacro"/>

View File

@ -1,7 +1,7 @@
# Controller Manager configuration # Controller Manager configuration
controller_manager: controller_manager:
ros__parameters: ros__parameters:
update_rate: 2000 # Hz update_rate: 1000 # Hz
# Define the available controllers # Define the available controllers
joint_state_broadcaster: joint_state_broadcaster:
@ -26,7 +26,7 @@ imu_sensor_broadcaster:
leg_pd_controller: leg_pd_controller:
ros__parameters: ros__parameters:
update_rate: 500 # Hz update_rate: 1000 # Hz
joints: joints:
- FR_hip_joint - FR_hip_joint
- FR_thigh_joint - FR_thigh_joint
@ -50,7 +50,7 @@ leg_pd_controller:
unitree_guide_controller: unitree_guide_controller:
ros__parameters: ros__parameters:
update_rate: 500 # Hz update_rate: 200 # Hz
command_prefix: "leg_pd_controller" command_prefix: "leg_pd_controller"
joints: joints:
- FR_hip_joint - FR_hip_joint

View File

@ -67,6 +67,24 @@
<box size="${trunk_length} ${trunk_width} ${trunk_height}"/> <box size="${trunk_length} ${trunk_width} ${trunk_height}"/>
</geometry> </geometry>
</collision> </collision>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.1881 0.04675 0.057"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0.285 0 0.01"/>
<geometry>
<cylinder length="0.05" radius="0.045"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0.293 0 -0.06"/>
<geometry>
<box size="0.047 0.047 0.047"/>
</geometry>
</collision>
<inertial> <inertial>
<origin rpy="0 0 0" xyz="${trunk_com_x} ${trunk_com_y} ${trunk_com_z}"/> <origin rpy="0 0 0" xyz="${trunk_com_x} ${trunk_com_y} ${trunk_com_z}"/>
<mass value="${trunk_mass}"/> <mass value="${trunk_mass}"/>

View File

@ -36,7 +36,15 @@ ros2 launch cyberdog_description visualize.launch.py
ros2 launch ocs2_quadruped_controller mujoco.launch.py pkg_description:=cyberdog_description ros2 launch ocs2_quadruped_controller mujoco.launch.py pkg_description:=cyberdog_description
``` ```
### Gazebo Simulator ### Gazebo Classic 11 (ROS2 Humble)
* Unitree Guide Controller
```bash
source ~/ros2_ws/install/setup.bash
ros2 launch unitree_guide_controller gazebo_classic.launch.py pkg_description:=cyberdog_description height:=0.31
```
### Gazebo Harmonic (ROS2 Jazzy)
* Unitree Guide Controller * Unitree Guide Controller
```bash ```bash

View File

@ -1,7 +1,7 @@
# Controller Manager configuration # Controller Manager configuration
controller_manager: controller_manager:
ros__parameters: ros__parameters:
update_rate: 2000 # Hz update_rate: 1000 # Hz
# Define the available controllers # Define the available controllers
joint_state_broadcaster: joint_state_broadcaster:
@ -23,6 +23,7 @@ imu_sensor_broadcaster:
leg_pd_controller: leg_pd_controller:
ros__parameters: ros__parameters:
update_rate: 1000 # Hz
joints: joints:
- FR_hip_joint - FR_hip_joint
- FR_thigh_joint - FR_thigh_joint
@ -48,6 +49,7 @@ unitree_guide_controller:
ros__parameters: ros__parameters:
command_prefix: "leg_pd_controller" command_prefix: "leg_pd_controller"
update_rate: 500 # Hz update_rate: 500 # Hz
stand_kd: 1.0
joints: joints:
- FR_hip_joint - FR_hip_joint
- FR_thigh_joint - FR_thigh_joint

View File

@ -55,9 +55,9 @@
<xacro:property name="abad_motorVelMax" value="30.9971"/> <xacro:property name="abad_motorVelMax" value="30.9971"/>
<xacro:property name="hip_motorVelMax" value="30.9971"/> <xacro:property name="hip_motorVelMax" value="30.9971"/>
<xacro:property name="knee_motorVelMax" value="30.9971"/> <xacro:property name="knee_motorVelMax" value="30.9971"/>
<xacro:property name="abad_damping" value="0.01"/> <xacro:property name="abad_damping" value="0.1"/>
<xacro:property name="hip_damping" value="0.01"/> <xacro:property name="hip_damping" value="0.1"/>
<xacro:property name="knee_damping" value="0.01"/> <xacro:property name="knee_damping" value="0.1"/>
<xacro:property name="abad_friction" value="0.1"/> <xacro:property name="abad_friction" value="0.1"/>
<xacro:property name="hip_friction" value="0.1"/> <xacro:property name="hip_friction" value="0.1"/>
<xacro:property name="knee_friction" value="0.1"/> <xacro:property name="knee_friction" value="0.1"/>

View File

@ -0,0 +1,238 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<ros2_control name="GazeboSystem" type="system">
<hardware>
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</hardware>
<joint name="FR_hip_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FR_thigh_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FR_calf_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_hip_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_thigh_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_calf_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RR_hip_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RR_thigh_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RR_calf_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RL_hip_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RL_thigh_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RL_calf_joint">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<sensor name="imu_sensor">
<state_interface name="orientation.x"/>
<state_interface name="orientation.y"/>
<state_interface name="orientation.z"/>
<state_interface name="orientation.w"/>
<state_interface name="angular_velocity.x"/>
<state_interface name="angular_velocity.y"/>
<state_interface name="angular_velocity.z"/>
<state_interface name="linear_acceleration.x"/>
<state_interface name="linear_acceleration.y"/>
<state_interface name="linear_acceleration.z"/>
</sensor>
</ros2_control>
<gazebo>
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
<parameters>$(find cyberdog_description)/config/gazebo.yaml</parameters>
</plugin>
</gazebo>
<gazebo reference="trunk">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
</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>
<!-- FL leg -->
<gazebo reference="FL_abad">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="FL_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="FL_knee">
<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>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<!-- FR leg -->
<gazebo reference="FR_abad">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="FR_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="FR_knee">
<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>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<!-- RL leg -->
<gazebo reference="RL_abad">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="RL_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="RL_knee">
<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>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<!-- RR leg -->
<gazebo reference="RR_abad">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="RR_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="RR_knee">
<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>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
</robot>

View File

@ -4,12 +4,18 @@
<xacro:arg name="ROBOT" default="cyber_dog"/> <xacro:arg name="ROBOT" default="cyber_dog"/>
<xacro:arg name="USE_LIDAR" default="false"/> <xacro:arg name="USE_LIDAR" default="false"/>
<xacro:arg name="GAZEBO" default="false"/> <xacro:arg name="GAZEBO" default="false"/>
<xacro:arg name="CLASSIC" default="false"/>
<xacro:include filename="const.xacro"/> <xacro:include filename="const.xacro"/>
<xacro:include filename="leg.xacro"/> <xacro:include filename="leg.xacro"/>
<xacro:if value="$(arg GAZEBO)"> <xacro:if value="$(arg GAZEBO)">
<xacro:if value="$(arg CLASSIC)">
<xacro:include filename="gazebo_classic.xacro"/>
</xacro:if>
<xacro:unless value="$(arg CLASSIC)">
<xacro:include filename="gazebo.xacro"/> <xacro:include filename="gazebo.xacro"/>
</xacro:unless>
</xacro:if> </xacro:if>
<xacro:unless value="$(arg GAZEBO)"> <xacro:unless value="$(arg GAZEBO)">
<xacro:include filename="ros2_control.xacro"/> <xacro:include filename="ros2_control.xacro"/>