add more support for gazebo classic simulationn
This commit is contained in:
parent
a6080328e0
commit
834ba68d4b
|
@ -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),
|
||||||
])
|
])
|
|
@ -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
|
||||||
|
|
|
@ -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
|
||||||
|
|
|
@ -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>
|
||||||
|
|
||||||
|
|
|
@ -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">
|
||||||
|
|
|
@ -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>
|
|
@ -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:include filename="$(find lite3_description)/xacro/gazebo.xacro"/>
|
<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: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"/>
|
||||||
|
|
|
@ -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
|
||||||
|
|
|
@ -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
|
||||||
|
|
|
@ -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>
|
|
@ -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:include filename="$(find x30_description)/xacro/gazebo.xacro"/>
|
<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: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"/>
|
||||||
|
|
|
@ -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
|
||||||
|
|
|
@ -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
|
||||||
|
|
|
@ -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>
|
|
@ -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>
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -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
|
||||||
|
|
|
@ -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
|
||||||
|
|
|
@ -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"/>
|
||||||
|
|
|
@ -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>
|
|
@ -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:include filename="$(find b2_description)/xacro/gazebo.xacro"/>
|
<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: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"/>
|
||||||
|
|
|
@ -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
|
||||||
|
|
|
@ -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
|
||||||
|
|
|
@ -2,158 +2,158 @@
|
||||||
|
|
||||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
<!-- Constants for robot dimensions -->
|
<!-- Constants for robot dimensions -->
|
||||||
<xacro:property name="PI" value="3.1415926535897931"/>
|
<xacro:property name="PI" value="3.1415926535897931"/>
|
||||||
<xacro:property name="stick_mass" value="0.00001"/>
|
<xacro:property name="stick_mass" value="0.00001"/>
|
||||||
|
|
||||||
<!-- simplified collision value -->
|
<!-- simplified collision value -->
|
||||||
<xacro:property name="trunk_width" value="0.0935"/>
|
<xacro:property name="trunk_width" value="0.0935"/>
|
||||||
<xacro:property name="trunk_length" value="0.3762"/>
|
<xacro:property name="trunk_length" value="0.3762"/>
|
||||||
<xacro:property name="trunk_height" value="0.114"/>
|
<xacro:property name="trunk_height" value="0.114"/>
|
||||||
<xacro:property name="hip_radius" value="0.046"/>
|
<xacro:property name="hip_radius" value="0.046"/>
|
||||||
<xacro:property name="hip_length" value="0.04"/>
|
<xacro:property name="hip_length" value="0.04"/>
|
||||||
<xacro:property name="thigh_shoulder_radius" value="0.041"/>
|
<xacro:property name="thigh_shoulder_radius" value="0.041"/>
|
||||||
<xacro:property name="thigh_shoulder_length" value="0.032"/>
|
<xacro:property name="thigh_shoulder_length" value="0.032"/>
|
||||||
<xacro:property name="thigh_width" value="0.0245"/>
|
<xacro:property name="thigh_width" value="0.0245"/>
|
||||||
<xacro:property name="thigh_height" value="0.034"/>
|
<xacro:property name="thigh_height" value="0.034"/>
|
||||||
<xacro:property name="calf_width" value="0.016"/>
|
<xacro:property name="calf_width" value="0.016"/>
|
||||||
<xacro:property name="calf_height" value="0.016"/>
|
<xacro:property name="calf_height" value="0.016"/>
|
||||||
<xacro:property name="foot_radius" value="0.02"/>
|
<xacro:property name="foot_radius" value="0.02"/>
|
||||||
<xacro:property name="stick_radius" value="0.01"/>
|
<xacro:property name="stick_radius" value="0.01"/>
|
||||||
<xacro:property name="stick_length" value="0.2"/>
|
<xacro:property name="stick_length" value="0.2"/>
|
||||||
|
|
||||||
<!-- kinematic value -->
|
<!-- kinematic value -->
|
||||||
<xacro:property name="thigh_offset" value="0.08"/>
|
<xacro:property name="thigh_offset" value="0.08"/>
|
||||||
<xacro:property name="thigh_length" value="0.213"/>
|
<xacro:property name="thigh_length" value="0.213"/>
|
||||||
<xacro:property name="calf_length" value="0.213"/>
|
<xacro:property name="calf_length" value="0.213"/>
|
||||||
|
|
||||||
<!-- leg offset from trunk center value -->
|
<!-- leg offset from trunk center value -->
|
||||||
<xacro:property name="leg_offset_x" value="0.1881"/>
|
<xacro:property name="leg_offset_x" value="0.1881"/>
|
||||||
<xacro:property name="leg_offset_y" value="0.04675"/>
|
<xacro:property name="leg_offset_y" value="0.04675"/>
|
||||||
<!-- <xacro:property name="trunk_offset_z" value="0.01675"/> -->
|
<!-- <xacro:property name="trunk_offset_z" value="0.01675"/> -->
|
||||||
<xacro:property name="hip_offset" value="0.08"/>
|
<xacro:property name="hip_offset" value="0.08"/>
|
||||||
|
|
||||||
<!-- offset of link and rotor locations (left front) -->
|
<!-- offset of link and rotor locations (left front) -->
|
||||||
<xacro:property name="hip_offset_x" value="0.1881"/>
|
<xacro:property name="hip_offset_x" value="0.1881"/>
|
||||||
<xacro:property name="hip_offset_y" value="0.04675"/>
|
<xacro:property name="hip_offset_y" value="0.04675"/>
|
||||||
<xacro:property name="hip_offset_z" value="0.0"/>
|
<xacro:property name="hip_offset_z" value="0.0"/>
|
||||||
<xacro:property name="hip_rotor_offset_x" value="0.11215"/>
|
<xacro:property name="hip_rotor_offset_x" value="0.11215"/>
|
||||||
<xacro:property name="hip_rotor_offset_y" value="0.04675"/>
|
<xacro:property name="hip_rotor_offset_y" value="0.04675"/>
|
||||||
<xacro:property name="hip_rotor_offset_z" value="0.0"/>
|
<xacro:property name="hip_rotor_offset_z" value="0.0"/>
|
||||||
|
|
||||||
<xacro:property name="thigh_offset_x" value="0"/>
|
<xacro:property name="thigh_offset_x" value="0"/>
|
||||||
<xacro:property name="thigh_offset_y" value="0.08"/>
|
<xacro:property name="thigh_offset_y" value="0.08"/>
|
||||||
<xacro:property name="thigh_offset_z" value="0.0"/>
|
<xacro:property name="thigh_offset_z" value="0.0"/>
|
||||||
<xacro:property name="thigh_rotor_offset_x" value="0.0"/>
|
<xacro:property name="thigh_rotor_offset_x" value="0.0"/>
|
||||||
<xacro:property name="thigh_rotor_offset_y" value="-0.00015"/>
|
<xacro:property name="thigh_rotor_offset_y" value="-0.00015"/>
|
||||||
<xacro:property name="thigh_rotor_offset_z" value="0.0"/>
|
<xacro:property name="thigh_rotor_offset_z" value="0.0"/>
|
||||||
|
|
||||||
<xacro:property name="calf_offset_x" value="0.0"/>
|
<xacro:property name="calf_offset_x" value="0.0"/>
|
||||||
<xacro:property name="calf_offset_y" value="0.0"/>
|
<xacro:property name="calf_offset_y" value="0.0"/>
|
||||||
<xacro:property name="calf_offset_z" value="-0.213"/>
|
<xacro:property name="calf_offset_z" value="-0.213"/>
|
||||||
<xacro:property name="calf_rotor_offset_x" value="0.0"/>
|
<xacro:property name="calf_rotor_offset_x" value="0.0"/>
|
||||||
<xacro:property name="calf_rotor_offset_y" value="-0.03235"/>
|
<xacro:property name="calf_rotor_offset_y" value="-0.03235"/>
|
||||||
<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"/>
|
||||||
<xacro:property name="hip_torque_max" value="23.7"/>
|
<xacro:property name="hip_torque_max" value="23.7"/>
|
||||||
<xacro:property name="thigh_position_max" value="4.501"/>
|
<xacro:property name="thigh_position_max" value="4.501"/>
|
||||||
<xacro:property name="thigh_position_min" value="-0.686"/>
|
<xacro:property name="thigh_position_min" value="-0.686"/>
|
||||||
<xacro:property name="thigh_velocity_max" value="30.1"/>
|
<xacro:property name="thigh_velocity_max" value="30.1"/>
|
||||||
<xacro:property name="thigh_torque_max" value="23.7"/>
|
<xacro:property name="thigh_torque_max" value="23.7"/>
|
||||||
<xacro:property name="calf_position_max" value="-0.888"/>
|
<xacro:property name="calf_position_max" value="-0.888"/>
|
||||||
<xacro:property name="calf_position_min" value="-2.818"/>
|
<xacro:property name="calf_position_min" value="-2.818"/>
|
||||||
<xacro:property name="calf_velocity_max" value="20.06"/>
|
<xacro:property name="calf_velocity_max" value="20.06"/>
|
||||||
<xacro:property name="calf_torque_max" value="35.55"/>
|
<xacro:property name="calf_torque_max" value="35.55"/>
|
||||||
|
|
||||||
<!-- dynamics inertial value total 12.84kg -->
|
<!-- dynamics inertial value total 12.84kg -->
|
||||||
<!-- trunk -->
|
<!-- trunk -->
|
||||||
<xacro:property name="trunk_mass" value="5.204"/>
|
<xacro:property name="trunk_mass" value="5.204"/>
|
||||||
<xacro:property name="trunk_com_x" value="0.0223"/>
|
<xacro:property name="trunk_com_x" value="0.0223"/>
|
||||||
<xacro:property name="trunk_com_y" value="0.002"/>
|
<xacro:property name="trunk_com_y" value="0.002"/>
|
||||||
<xacro:property name="trunk_com_z" value="-0.0005"/>
|
<xacro:property name="trunk_com_z" value="-0.0005"/>
|
||||||
<xacro:property name="trunk_ixx" value="0.0168128557"/>
|
<xacro:property name="trunk_ixx" value="0.0168128557"/>
|
||||||
<xacro:property name="trunk_ixy" value="-0.0002296769"/>
|
<xacro:property name="trunk_ixy" value="-0.0002296769"/>
|
||||||
<xacro:property name="trunk_ixz" value="-0.0002945293"/>
|
<xacro:property name="trunk_ixz" value="-0.0002945293"/>
|
||||||
<xacro:property name="trunk_iyy" value="0.063009565"/>
|
<xacro:property name="trunk_iyy" value="0.063009565"/>
|
||||||
<xacro:property name="trunk_iyz" value="-0.0000418731"/>
|
<xacro:property name="trunk_iyz" value="-0.0000418731"/>
|
||||||
<xacro:property name="trunk_izz" value="0.0716547275"/>
|
<xacro:property name="trunk_izz" value="0.0716547275"/>
|
||||||
|
|
||||||
<!-- hip (left front) -->
|
<!-- hip (left front) -->
|
||||||
<xacro:property name="hip_mass" value="0.591"/>
|
<xacro:property name="hip_mass" value="0.591"/>
|
||||||
<xacro:property name="hip_com_x" value="-0.005657"/>
|
<xacro:property name="hip_com_x" value="-0.005657"/>
|
||||||
<xacro:property name="hip_com_y" value="-0.008752"/>
|
<xacro:property name="hip_com_y" value="-0.008752"/>
|
||||||
<xacro:property name="hip_com_z" value="-0.000102"/>
|
<xacro:property name="hip_com_z" value="-0.000102"/>
|
||||||
<xacro:property name="hip_ixx" value="0.000334008405"/>
|
<xacro:property name="hip_ixx" value="0.000334008405"/>
|
||||||
<xacro:property name="hip_ixy" value="-0.000010826066"/>
|
<xacro:property name="hip_ixy" value="-0.000010826066"/>
|
||||||
<xacro:property name="hip_ixz" value="0.000001290732"/>
|
<xacro:property name="hip_ixz" value="0.000001290732"/>
|
||||||
<xacro:property name="hip_iyy" value="0.000619101213"/>
|
<xacro:property name="hip_iyy" value="0.000619101213"/>
|
||||||
<xacro:property name="hip_iyz" value="0.000001643194"/>
|
<xacro:property name="hip_iyz" value="0.000001643194"/>
|
||||||
<xacro:property name="hip_izz" value="0.00040057614"/>
|
<xacro:property name="hip_izz" value="0.00040057614"/>
|
||||||
|
|
||||||
<xacro:property name="hip_rotor_mass" value="0.089"/>
|
<xacro:property name="hip_rotor_mass" value="0.089"/>
|
||||||
<xacro:property name="hip_rotor_com_x" value="0.0"/>
|
<xacro:property name="hip_rotor_com_x" value="0.0"/>
|
||||||
<xacro:property name="hip_rotor_com_y" value="0.0"/>
|
<xacro:property name="hip_rotor_com_y" value="0.0"/>
|
||||||
<xacro:property name="hip_rotor_com_z" value="0.0"/>
|
<xacro:property name="hip_rotor_com_z" value="0.0"/>
|
||||||
<xacro:property name="hip_rotor_ixx" value="0.000111842"/>
|
<xacro:property name="hip_rotor_ixx" value="0.000111842"/>
|
||||||
<xacro:property name="hip_rotor_ixy" value="0.0"/>
|
<xacro:property name="hip_rotor_ixy" value="0.0"/>
|
||||||
<xacro:property name="hip_rotor_ixz" value="0.0"/>
|
<xacro:property name="hip_rotor_ixz" value="0.0"/>
|
||||||
<xacro:property name="hip_rotor_iyy" value="0.000059647"/>
|
<xacro:property name="hip_rotor_iyy" value="0.000059647"/>
|
||||||
<xacro:property name="hip_rotor_iyz" value="0.0"/>
|
<xacro:property name="hip_rotor_iyz" value="0.0"/>
|
||||||
<xacro:property name="hip_rotor_izz" value="0.000059647"/>
|
<xacro:property name="hip_rotor_izz" value="0.000059647"/>
|
||||||
|
|
||||||
<!-- thigh -->
|
<!-- thigh -->
|
||||||
<xacro:property name="thigh_mass" value="0.92"/>
|
<xacro:property name="thigh_mass" value="0.92"/>
|
||||||
<xacro:property name="thigh_com_x" value="-0.003342"/>
|
<xacro:property name="thigh_com_x" value="-0.003342"/>
|
||||||
<xacro:property name="thigh_com_y" value="-0.018054"/>
|
<xacro:property name="thigh_com_y" value="-0.018054"/>
|
||||||
<xacro:property name="thigh_com_z" value="-0.033451"/>
|
<xacro:property name="thigh_com_z" value="-0.033451"/>
|
||||||
<xacro:property name="thigh_ixx" value="0.004431760472"/>
|
<xacro:property name="thigh_ixx" value="0.004431760472"/>
|
||||||
<xacro:property name="thigh_ixy" value="0.000057496807"/>
|
<xacro:property name="thigh_ixy" value="0.000057496807"/>
|
||||||
<xacro:property name="thigh_ixz" value="-0.000218457134"/>
|
<xacro:property name="thigh_ixz" value="-0.000218457134"/>
|
||||||
<xacro:property name="thigh_iyy" value="0.004485671726"/>
|
<xacro:property name="thigh_iyy" value="0.004485671726"/>
|
||||||
<xacro:property name="thigh_iyz" value="0.000572001265"/>
|
<xacro:property name="thigh_iyz" value="0.000572001265"/>
|
||||||
<xacro:property name="thigh_izz" value="0.000740309489"/>
|
<xacro:property name="thigh_izz" value="0.000740309489"/>
|
||||||
|
|
||||||
<xacro:property name="thigh_rotor_mass" value="0.089"/>
|
<xacro:property name="thigh_rotor_mass" value="0.089"/>
|
||||||
<xacro:property name="thigh_rotor_com_x" value="0.0"/>
|
<xacro:property name="thigh_rotor_com_x" value="0.0"/>
|
||||||
<xacro:property name="thigh_rotor_com_y" value="0.0"/>
|
<xacro:property name="thigh_rotor_com_y" value="0.0"/>
|
||||||
<xacro:property name="thigh_rotor_com_z" value="0.0"/>
|
<xacro:property name="thigh_rotor_com_z" value="0.0"/>
|
||||||
<xacro:property name="thigh_rotor_ixx" value="0.000059647"/>
|
<xacro:property name="thigh_rotor_ixx" value="0.000059647"/>
|
||||||
<xacro:property name="thigh_rotor_ixy" value="0.0"/>
|
<xacro:property name="thigh_rotor_ixy" value="0.0"/>
|
||||||
<xacro:property name="thigh_rotor_ixz" value="0.0"/>
|
<xacro:property name="thigh_rotor_ixz" value="0.0"/>
|
||||||
<xacro:property name="thigh_rotor_iyy" value="0.000111842"/>
|
<xacro:property name="thigh_rotor_iyy" value="0.000111842"/>
|
||||||
<xacro:property name="thigh_rotor_iyz" value="0.0"/>
|
<xacro:property name="thigh_rotor_iyz" value="0.0"/>
|
||||||
<xacro:property name="thigh_rotor_izz" value="0.000059647"/>
|
<xacro:property name="thigh_rotor_izz" value="0.000059647"/>
|
||||||
|
|
||||||
<!-- calf -->
|
<!-- calf -->
|
||||||
<xacro:property name="calf_mass" value="0.135862"/>
|
<xacro:property name="calf_mass" value="0.135862"/>
|
||||||
<xacro:property name="calf_com_x" value="0.006197"/>
|
<xacro:property name="calf_com_x" value="0.006197"/>
|
||||||
<xacro:property name="calf_com_y" value="0.001408"/>
|
<xacro:property name="calf_com_y" value="0.001408"/>
|
||||||
<xacro:property name="calf_com_z" value="-0.116695"/>
|
<xacro:property name="calf_com_z" value="-0.116695"/>
|
||||||
<xacro:property name="calf_ixx" value="0.001088793059"/>
|
<xacro:property name="calf_ixx" value="0.001088793059"/>
|
||||||
<xacro:property name="calf_ixy" value="-0.000000255679"/>
|
<xacro:property name="calf_ixy" value="-0.000000255679"/>
|
||||||
<xacro:property name="calf_ixz" value="0.000007117814"/>
|
<xacro:property name="calf_ixz" value="0.000007117814"/>
|
||||||
<xacro:property name="calf_iyy" value="0.001100428748"/>
|
<xacro:property name="calf_iyy" value="0.001100428748"/>
|
||||||
<xacro:property name="calf_iyz" value="0.000002077264"/>
|
<xacro:property name="calf_iyz" value="0.000002077264"/>
|
||||||
<xacro:property name="calf_izz" value="0.000024787446"/>
|
<xacro:property name="calf_izz" value="0.000024787446"/>
|
||||||
|
|
||||||
<xacro:property name="calf_rotor_mass" value="0.089"/>
|
<xacro:property name="calf_rotor_mass" value="0.089"/>
|
||||||
<xacro:property name="calf_rotor_com_x" value="0.0"/>
|
<xacro:property name="calf_rotor_com_x" value="0.0"/>
|
||||||
<xacro:property name="calf_rotor_com_y" value="0.0"/>
|
<xacro:property name="calf_rotor_com_y" value="0.0"/>
|
||||||
<xacro:property name="calf_rotor_com_z" value="0.0"/>
|
<xacro:property name="calf_rotor_com_z" value="0.0"/>
|
||||||
<xacro:property name="calf_rotor_ixx" value="0.000059647"/>
|
<xacro:property name="calf_rotor_ixx" value="0.000059647"/>
|
||||||
<xacro:property name="calf_rotor_ixy" value="0.0"/>
|
<xacro:property name="calf_rotor_ixy" value="0.0"/>
|
||||||
<xacro:property name="calf_rotor_ixz" value="0.0"/>
|
<xacro:property name="calf_rotor_ixz" value="0.0"/>
|
||||||
<xacro:property name="calf_rotor_iyy" value="0.000111842"/>
|
<xacro:property name="calf_rotor_iyy" value="0.000111842"/>
|
||||||
<xacro:property name="calf_rotor_iyz" value="0.0"/>
|
<xacro:property name="calf_rotor_iyz" value="0.0"/>
|
||||||
<xacro:property name="calf_rotor_izz" value="0.000059647"/>
|
<xacro:property name="calf_rotor_izz" value="0.000059647"/>
|
||||||
|
|
||||||
<!-- foot -->
|
<!-- foot -->
|
||||||
<xacro:property name="foot_mass" value="0.06"/>
|
<xacro:property name="foot_mass" value="0.06"/>
|
||||||
|
|
||||||
</robot>
|
</robot>
|
||||||
|
|
|
@ -1,87 +1,87 @@
|
||||||
<?xml version="1.0"?>
|
<?xml version="1.0"?>
|
||||||
|
|
||||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
<xacro:macro name="depthCamera" params="camID name *origin">
|
<xacro:macro name="depthCamera" params="camID name *origin">
|
||||||
<joint name="camera_joint_${name}" type="fixed">
|
<joint name="camera_joint_${name}" type="fixed">
|
||||||
<xacro:insert_block name="origin"/>
|
<xacro:insert_block name="origin"/>
|
||||||
<parent link="trunk"/>
|
<parent link="trunk"/>
|
||||||
<child link="camera_${name}"/>
|
<child link="camera_${name}"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="camera_${name}">
|
<link name="camera_${name}">
|
||||||
<collision>
|
<collision>
|
||||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size=".001 .001 .001"/>
|
<box size=".001 .001 .001"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
|
|
||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="file://$(find go1_description)/meshes/depthCamera.dae" scale="1 1 1"/>
|
<mesh filename="file://$(find go1_description)/meshes/depthCamera.dae" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</visual>
|
</visual>
|
||||||
|
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="1e-5" />
|
<mass value="1e-5"/>
|
||||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
|
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="camera_optical_joint_${name}" type="fixed">
|
<joint name="camera_optical_joint_${name}" type="fixed">
|
||||||
<origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}"/>
|
<origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}"/>
|
||||||
<parent link="camera_${name}"/>
|
<parent link="camera_${name}"/>
|
||||||
<child link="camera_optical_${name}"/>
|
<child link="camera_optical_${name}"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="camera_optical_${name}">
|
<link name="camera_optical_${name}">
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<!-- <gazebo reference="camera_${name}">-->
|
<!-- <gazebo reference="camera_${name}">-->
|
||||||
<!-- <!– <material>Gazebo/Black</material> –>-->
|
<!-- <!– <material>Gazebo/Black</material> –>-->
|
||||||
<!-- <sensor name="camera_${name}_camera" type="depth">-->
|
<!-- <sensor name="camera_${name}_camera" type="depth">-->
|
||||||
<!-- <update_rate>16</update_rate>-->
|
<!-- <update_rate>16</update_rate>-->
|
||||||
<!-- <camera>-->
|
<!-- <camera>-->
|
||||||
<!-- <horizontal_fov>2.094</horizontal_fov>-->
|
<!-- <horizontal_fov>2.094</horizontal_fov>-->
|
||||||
<!-- <image>-->
|
<!-- <image>-->
|
||||||
<!-- <width>928</width>-->
|
<!-- <width>928</width>-->
|
||||||
<!-- <height>800</height>-->
|
<!-- <height>800</height>-->
|
||||||
<!-- <format>R8G8B8</format>-->
|
<!-- <format>R8G8B8</format>-->
|
||||||
<!-- </image>-->
|
<!-- </image>-->
|
||||||
<!-- <clip>-->
|
<!-- <clip>-->
|
||||||
<!-- <near>0.1</near>-->
|
<!-- <near>0.1</near>-->
|
||||||
<!-- <far>5</far>-->
|
<!-- <far>5</far>-->
|
||||||
<!-- </clip>-->
|
<!-- </clip>-->
|
||||||
<!-- </camera>-->
|
<!-- </camera>-->
|
||||||
<!-- <plugin name="camera_${name}_controller" filename="libgazebo_ros_openni_kinect.so">-->
|
<!-- <plugin name="camera_${name}_controller" filename="libgazebo_ros_openni_kinect.so">-->
|
||||||
<!-- <baseline>0.025</baseline>-->
|
<!-- <baseline>0.025</baseline>-->
|
||||||
<!-- <alwaysOn>true</alwaysOn>-->
|
<!-- <alwaysOn>true</alwaysOn>-->
|
||||||
<!-- <updateRate>0.0</updateRate>-->
|
<!-- <updateRate>0.0</updateRate>-->
|
||||||
<!-- <cameraName>camera_${name}_ir</cameraName>-->
|
<!-- <cameraName>camera_${name}_ir</cameraName>-->
|
||||||
<!-- <imageTopicName>/camera_${name}/color/image_raw</imageTopicName>-->
|
<!-- <imageTopicName>/camera_${name}/color/image_raw</imageTopicName>-->
|
||||||
<!-- <cameraInfoTopicName>/camera_${name}/color/camera_info</cameraInfoTopicName>-->
|
<!-- <cameraInfoTopicName>/camera_${name}/color/camera_info</cameraInfoTopicName>-->
|
||||||
<!-- <depthImageTopicName>/camera_${name}/depth/image_raw</depthImageTopicName>-->
|
<!-- <depthImageTopicName>/camera_${name}/depth/image_raw</depthImageTopicName>-->
|
||||||
<!-- <depthImageInfoTopicName>/camera_${name}/depth/camera_info</depthImageInfoTopicName>-->
|
<!-- <depthImageInfoTopicName>/camera_${name}/depth/camera_info</depthImageInfoTopicName>-->
|
||||||
<!-- <!– <pointCloudTopicName>/camera_${name}/depth/points</pointCloudTopicName> –>-->
|
<!-- <!– <pointCloudTopicName>/camera_${name}/depth/points</pointCloudTopicName> –>-->
|
||||||
<!-- <pointCloudTopicName>/cam${camID}/point_cloud_${name}</pointCloudTopicName>-->
|
<!-- <pointCloudTopicName>/cam${camID}/point_cloud_${name}</pointCloudTopicName>-->
|
||||||
<!-- <frameName>camera_optical_${name}</frameName>-->
|
<!-- <frameName>camera_optical_${name}</frameName>-->
|
||||||
<!-- <pointCloudCutoff>0.1</pointCloudCutoff>-->
|
<!-- <pointCloudCutoff>0.1</pointCloudCutoff>-->
|
||||||
<!-- <pointCloudCutoffMax>1.5</pointCloudCutoffMax>-->
|
<!-- <pointCloudCutoffMax>1.5</pointCloudCutoffMax>-->
|
||||||
<!-- <distortionK1>0.0</distortionK1>-->
|
<!-- <distortionK1>0.0</distortionK1>-->
|
||||||
<!-- <distortionK2>0.0</distortionK2>-->
|
<!-- <distortionK2>0.0</distortionK2>-->
|
||||||
<!-- <distortionK3>0.0</distortionK3>-->
|
<!-- <distortionK3>0.0</distortionK3>-->
|
||||||
<!-- <distortionT1>0.0</distortionT1>-->
|
<!-- <distortionT1>0.0</distortionT1>-->
|
||||||
<!-- <distortionT2>0.0</distortionT2>-->
|
<!-- <distortionT2>0.0</distortionT2>-->
|
||||||
<!-- <CxPrime>0</CxPrime>-->
|
<!-- <CxPrime>0</CxPrime>-->
|
||||||
<!-- <Cx>0.0045</Cx>-->
|
<!-- <Cx>0.0045</Cx>-->
|
||||||
<!-- <Cy>0.0039</Cy>-->
|
<!-- <Cy>0.0039</Cy>-->
|
||||||
<!-- <focalLength>0</focalLength>-->
|
<!-- <focalLength>0</focalLength>-->
|
||||||
<!-- <hackBaseline>0</hackBaseline>-->
|
<!-- <hackBaseline>0</hackBaseline>-->
|
||||||
<!-- </plugin>-->
|
<!-- </plugin>-->
|
||||||
<!-- </sensor>-->
|
<!-- </sensor>-->
|
||||||
<!-- </gazebo>-->
|
<!-- </gazebo>-->
|
||||||
|
|
||||||
</xacro:macro>
|
</xacro:macro>
|
||||||
</robot>
|
</robot>
|
|
@ -1,188 +1,188 @@
|
||||||
<?xml version="1.0"?>
|
<?xml version="1.0"?>
|
||||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
<ros2_control name="GazeboSystem" type="system">
|
<ros2_control name="GazeboSystem" type="system">
|
||||||
<hardware>
|
<hardware>
|
||||||
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
|
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
|
||||||
</hardware>
|
</hardware>
|
||||||
|
|
||||||
<joint name="FR_hip_joint">
|
<joint name="FR_hip_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FR_thigh_joint">
|
<joint name="FR_thigh_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FR_calf_joint">
|
<joint name="FR_calf_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FL_hip_joint">
|
<joint name="FL_hip_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FL_thigh_joint">
|
<joint name="FL_thigh_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FL_calf_joint">
|
<joint name="FL_calf_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RR_hip_joint">
|
<joint name="RR_hip_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RR_thigh_joint">
|
<joint name="RR_thigh_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RR_calf_joint">
|
<joint name="RR_calf_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RL_hip_joint">
|
<joint name="RL_hip_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RL_thigh_joint">
|
<joint name="RL_thigh_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RL_calf_joint">
|
<joint name="RL_calf_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<sensor name="imu_sensor">
|
<sensor name="imu_sensor">
|
||||||
<state_interface name="orientation.x"/>
|
<state_interface name="orientation.x"/>
|
||||||
<state_interface name="orientation.y"/>
|
<state_interface name="orientation.y"/>
|
||||||
<state_interface name="orientation.z"/>
|
<state_interface name="orientation.z"/>
|
||||||
<state_interface name="orientation.w"/>
|
<state_interface name="orientation.w"/>
|
||||||
<state_interface name="angular_velocity.x"/>
|
<state_interface name="angular_velocity.x"/>
|
||||||
<state_interface name="angular_velocity.y"/>
|
<state_interface name="angular_velocity.y"/>
|
||||||
<state_interface name="angular_velocity.z"/>
|
<state_interface name="angular_velocity.z"/>
|
||||||
<state_interface name="linear_acceleration.x"/>
|
<state_interface name="linear_acceleration.x"/>
|
||||||
<state_interface name="linear_acceleration.y"/>
|
<state_interface name="linear_acceleration.y"/>
|
||||||
<state_interface name="linear_acceleration.z"/>
|
<state_interface name="linear_acceleration.z"/>
|
||||||
</sensor>
|
</sensor>
|
||||||
</ros2_control>
|
</ros2_control>
|
||||||
|
|
||||||
<gazebo>
|
<gazebo>
|
||||||
<plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
|
<plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
|
||||||
<parameters>$(find go1_description)/config/gazebo.yaml</parameters>
|
<parameters>$(find go1_description)/config/gazebo.yaml</parameters>
|
||||||
</plugin>
|
</plugin>
|
||||||
<plugin filename="gz-sim-imu-system"
|
<plugin filename="gz-sim-imu-system"
|
||||||
name="gz::sim::systems::Imu">
|
name="gz::sim::systems::Imu">
|
||||||
</plugin>
|
</plugin>
|
||||||
</gazebo>
|
</gazebo>
|
||||||
|
|
||||||
<gazebo reference="trunk">
|
<gazebo reference="trunk">
|
||||||
<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>
|
||||||
</gazebo>
|
</gazebo>
|
||||||
|
|
||||||
<gazebo reference="imu_link">
|
<gazebo reference="imu_link">
|
||||||
<sensor name="imu_sensor" type="imu">
|
<sensor name="imu_sensor" type="imu">
|
||||||
<always_on>1</always_on>
|
<always_on>1</always_on>
|
||||||
<update_rate>500</update_rate>
|
<update_rate>500</update_rate>
|
||||||
<visualize>true</visualize>
|
<visualize>true</visualize>
|
||||||
<topic>imu</topic>
|
<topic>imu</topic>
|
||||||
<imu>
|
<imu>
|
||||||
<angular_velocity>
|
<angular_velocity>
|
||||||
<x>
|
<x>
|
||||||
<noise type="gaussian">
|
<noise type="gaussian">
|
||||||
<mean>0.0</mean>
|
<mean>0.0</mean>
|
||||||
<stddev>2e-4</stddev>
|
<stddev>2e-4</stddev>
|
||||||
<bias_mean>0.0000075</bias_mean>
|
<bias_mean>0.0000075</bias_mean>
|
||||||
<bias_stddev>0.0000008</bias_stddev>
|
<bias_stddev>0.0000008</bias_stddev>
|
||||||
</noise>
|
</noise>
|
||||||
</x>
|
</x>
|
||||||
<y>
|
<y>
|
||||||
<noise type="gaussian">
|
<noise type="gaussian">
|
||||||
<mean>0.0</mean>
|
<mean>0.0</mean>
|
||||||
<stddev>2e-4</stddev>
|
<stddev>2e-4</stddev>
|
||||||
<bias_mean>0.0000075</bias_mean>
|
<bias_mean>0.0000075</bias_mean>
|
||||||
<bias_stddev>0.0000008</bias_stddev>
|
<bias_stddev>0.0000008</bias_stddev>
|
||||||
</noise>
|
</noise>
|
||||||
</y>
|
</y>
|
||||||
<z>
|
<z>
|
||||||
<noise type="gaussian">
|
<noise type="gaussian">
|
||||||
<mean>0.0</mean>
|
<mean>0.0</mean>
|
||||||
<stddev>2e-4</stddev>
|
<stddev>2e-4</stddev>
|
||||||
<bias_mean>0.0000075</bias_mean>
|
<bias_mean>0.0000075</bias_mean>
|
||||||
<bias_stddev>0.0000008</bias_stddev>
|
<bias_stddev>0.0000008</bias_stddev>
|
||||||
</noise>
|
</noise>
|
||||||
</z>
|
</z>
|
||||||
</angular_velocity>
|
</angular_velocity>
|
||||||
<linear_acceleration>
|
<linear_acceleration>
|
||||||
<x>
|
<x>
|
||||||
<noise type="gaussian">
|
<noise type="gaussian">
|
||||||
<mean>0.0</mean>
|
<mean>0.0</mean>
|
||||||
<stddev>1.7e-2</stddev>
|
<stddev>1.7e-2</stddev>
|
||||||
<bias_mean>0.1</bias_mean>
|
<bias_mean>0.1</bias_mean>
|
||||||
<bias_stddev>0.001</bias_stddev>
|
<bias_stddev>0.001</bias_stddev>
|
||||||
</noise>
|
</noise>
|
||||||
</x>
|
</x>
|
||||||
<y>
|
<y>
|
||||||
<noise type="gaussian">
|
<noise type="gaussian">
|
||||||
<mean>0.0</mean>
|
<mean>0.0</mean>
|
||||||
<stddev>1.7e-2</stddev>
|
<stddev>1.7e-2</stddev>
|
||||||
<bias_mean>0.1</bias_mean>
|
<bias_mean>0.1</bias_mean>
|
||||||
<bias_stddev>0.001</bias_stddev>
|
<bias_stddev>0.001</bias_stddev>
|
||||||
</noise>
|
</noise>
|
||||||
</y>
|
</y>
|
||||||
<z>
|
<z>
|
||||||
<noise type="gaussian">
|
<noise type="gaussian">
|
||||||
<mean>0.0</mean>
|
<mean>0.0</mean>
|
||||||
<stddev>1.7e-2</stddev>
|
<stddev>1.7e-2</stddev>
|
||||||
<bias_mean>0.1</bias_mean>
|
<bias_mean>0.1</bias_mean>
|
||||||
<bias_stddev>0.001</bias_stddev>
|
<bias_stddev>0.001</bias_stddev>
|
||||||
</noise>
|
</noise>
|
||||||
</z>
|
</z>
|
||||||
</linear_acceleration>
|
</linear_acceleration>
|
||||||
</imu>
|
</imu>
|
||||||
</sensor>
|
</sensor>
|
||||||
</gazebo>
|
</gazebo>
|
||||||
<gazebo reference="imu_joint">
|
<gazebo reference="imu_joint">
|
||||||
<disableFixedJointLumping>true</disableFixedJointLumping>
|
<disableFixedJointLumping>true</disableFixedJointLumping>
|
||||||
</gazebo>
|
</gazebo>
|
||||||
|
|
||||||
</robot>
|
</robot>
|
||||||
|
|
|
@ -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>
|
|
@ -2,280 +2,280 @@
|
||||||
|
|
||||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
<xacro:include filename="$(find go1_description)/xacro/transmission.xacro"/>
|
<xacro:include filename="$(find go1_description)/xacro/transmission.xacro"/>
|
||||||
|
|
||||||
<xacro:macro name="leg" params="name mirror mirror_dae front_hind front_hind_dae">
|
<xacro:macro name="leg" params="name mirror mirror_dae front_hind front_hind_dae">
|
||||||
|
|
||||||
<joint name="${name}_hip_joint" type="revolute">
|
<joint name="${name}_hip_joint" type="revolute">
|
||||||
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == True)}">
|
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == True)}">
|
||||||
<origin rpy="0 0 0" xyz="${leg_offset_x} ${-leg_offset_y} 0"/>
|
<origin rpy="0 0 0" xyz="${leg_offset_x} ${-leg_offset_y} 0"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == True)}">
|
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == True)}">
|
||||||
<origin rpy="0 0 0" xyz="${leg_offset_x} ${leg_offset_y} 0"/>
|
<origin rpy="0 0 0" xyz="${leg_offset_x} ${leg_offset_y} 0"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == False)}">
|
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == False)}">
|
||||||
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${-leg_offset_y} 0"/>
|
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${-leg_offset_y} 0"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == False)}">
|
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == False)}">
|
||||||
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${leg_offset_y} 0"/>
|
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${leg_offset_y} 0"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<parent link="trunk"/>
|
<parent link="trunk"/>
|
||||||
<child link="${name}_hip"/>
|
<child link="${name}_hip"/>
|
||||||
<axis xyz="1 0 0"/>
|
<axis xyz="1 0 0"/>
|
||||||
<dynamics damping="${damping}" friction="${friction}"/>
|
<dynamics damping="${damping}" friction="${friction}"/>
|
||||||
<xacro:if value="${(mirror_dae == True)}">
|
<xacro:if value="${(mirror_dae == True)}">
|
||||||
<limit effort="${hip_torque_max}" velocity="${hip_velocity_max}" lower="${hip_position_min}"
|
<limit effort="${hip_torque_max}" velocity="${hip_velocity_max}" lower="${hip_position_min}"
|
||||||
upper="${hip_position_max}"/>
|
upper="${hip_position_max}"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<xacro:if value="${(mirror_dae == False)}">
|
<xacro:if value="${(mirror_dae == False)}">
|
||||||
<limit effort="${hip_torque_max}" velocity="${hip_velocity_max}" lower="${-hip_position_max}"
|
<limit effort="${hip_torque_max}" velocity="${hip_velocity_max}" lower="${-hip_position_max}"
|
||||||
upper="${-hip_position_min}"/>
|
upper="${-hip_position_min}"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="${name}_hip_rotor_joint" type="fixed">
|
<joint name="${name}_hip_rotor_joint" type="fixed">
|
||||||
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == True)}">
|
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == True)}">
|
||||||
<origin rpy="0 0 0" xyz="${hip_rotor_offset_x} ${-hip_rotor_offset_y} 0"/>
|
<origin rpy="0 0 0" xyz="${hip_rotor_offset_x} ${-hip_rotor_offset_y} 0"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == True)}">
|
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == True)}">
|
||||||
<origin rpy="0 0 0" xyz="${hip_rotor_offset_x} ${hip_rotor_offset_y} 0"/>
|
<origin rpy="0 0 0" xyz="${hip_rotor_offset_x} ${hip_rotor_offset_y} 0"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == False)}">
|
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == False)}">
|
||||||
<origin rpy="0 0 0" xyz="${-hip_rotor_offset_x} ${-hip_rotor_offset_y} 0"/>
|
<origin rpy="0 0 0" xyz="${-hip_rotor_offset_x} ${-hip_rotor_offset_y} 0"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == False)}">
|
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == False)}">
|
||||||
<origin rpy="0 0 0" xyz="${-hip_rotor_offset_x} ${hip_rotor_offset_y} 0"/>
|
<origin rpy="0 0 0" xyz="${-hip_rotor_offset_x} ${hip_rotor_offset_y} 0"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<parent link="trunk"/>
|
<parent link="trunk"/>
|
||||||
<child link="${name}_hip_rotor"/>
|
<child link="${name}_hip_rotor"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="${name}_hip">
|
<link name="${name}_hip">
|
||||||
<visual>
|
<visual>
|
||||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == True)}">
|
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == True)}">
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == True)}">
|
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == True)}">
|
||||||
<origin rpy="${PI} 0 0" xyz="0 0 0"/>
|
<origin rpy="${PI} 0 0" xyz="0 0 0"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == False)}">
|
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == False)}">
|
||||||
<origin rpy="0 ${PI} 0" xyz="0 0 0"/>
|
<origin rpy="0 ${PI} 0" xyz="0 0 0"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == False)}">
|
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == False)}">
|
||||||
<origin rpy="${PI} ${PI} 0" xyz="0 0 0"/>
|
<origin rpy="${PI} ${PI} 0" xyz="0 0 0"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="file://$(find go1_description)/meshes/hip.dae" scale="1 1 1"/>
|
<mesh filename="file://$(find go1_description)/meshes/hip.dae" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="deep-grey"/>
|
<material name="deep-grey"/>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<origin rpy="${PI/2.0} 0 0" xyz="0 ${hip_offset*mirror} 0"/>
|
<origin rpy="${PI/2.0} 0 0" xyz="0 ${hip_offset*mirror} 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<cylinder length="${hip_length}" radius="${hip_radius}"/>
|
<cylinder length="${hip_length}" radius="${hip_radius}"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin rpy="0 0 0" xyz="${hip_com_x*front_hind} ${hip_com_y*mirror} ${hip_com_z}"/>
|
<origin rpy="0 0 0" xyz="${hip_com_x*front_hind} ${hip_com_y*mirror} ${hip_com_z}"/>
|
||||||
<mass value="${hip_mass}"/>
|
<mass value="${hip_mass}"/>
|
||||||
<inertia
|
<inertia
|
||||||
ixx="${hip_ixx}" ixy="${hip_ixy*mirror*front_hind}" ixz="${hip_ixz*front_hind}"
|
ixx="${hip_ixx}" ixy="${hip_ixy*mirror*front_hind}" ixz="${hip_ixz*front_hind}"
|
||||||
iyy="${hip_iyy}" iyz="${hip_iyz*mirror}"
|
iyy="${hip_iyy}" iyz="${hip_iyz*mirror}"
|
||||||
izz="${hip_izz}"/>
|
izz="${hip_izz}"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link name="${name}_hip_rotor">
|
<link name="${name}_hip_rotor">
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 0"/>
|
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<cylinder length="0.02" radius="0.035"/>
|
<cylinder length="0.02" radius="0.035"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</visual>
|
</visual>
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin rpy="0 0 0" xyz="${hip_rotor_com_x} ${hip_rotor_com_y} ${hip_rotor_com_z}"/>
|
<origin rpy="0 0 0" xyz="${hip_rotor_com_x} ${hip_rotor_com_y} ${hip_rotor_com_z}"/>
|
||||||
<mass value="${hip_rotor_mass}"/>
|
<mass value="${hip_rotor_mass}"/>
|
||||||
<inertia
|
<inertia
|
||||||
ixx="${hip_rotor_ixx}" ixy="${hip_rotor_ixy}" ixz="${hip_rotor_ixz}"
|
ixx="${hip_rotor_ixx}" ixy="${hip_rotor_ixy}" ixz="${hip_rotor_ixz}"
|
||||||
iyy="${hip_rotor_iyy}" iyz="${hip_rotor_iyz}"
|
iyy="${hip_rotor_iyy}" iyz="${hip_rotor_iyz}"
|
||||||
izz="${hip_rotor_izz}"/>
|
izz="${hip_rotor_izz}"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="${name}_thigh_joint" type="revolute">
|
<joint name="${name}_thigh_joint" type="revolute">
|
||||||
<origin rpy="0 0 0" xyz="0 ${thigh_offset*mirror} 0"/>
|
<origin rpy="0 0 0" xyz="0 ${thigh_offset*mirror} 0"/>
|
||||||
<parent link="${name}_hip"/>
|
<parent link="${name}_hip"/>
|
||||||
<child link="${name}_thigh"/>
|
<child link="${name}_thigh"/>
|
||||||
<axis xyz="0 1 0"/>
|
<axis xyz="0 1 0"/>
|
||||||
<dynamics damping="${damping}" friction="${friction}"/>
|
<dynamics damping="${damping}" friction="${friction}"/>
|
||||||
<limit effort="${thigh_torque_max}" velocity="${thigh_velocity_max}" lower="${thigh_position_min}"
|
<limit effort="${thigh_torque_max}" velocity="${thigh_velocity_max}" lower="${thigh_position_min}"
|
||||||
upper="${thigh_position_max}"/>
|
upper="${thigh_position_max}"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="${name}_thigh_rotor_joint" type="fixed">
|
<joint name="${name}_thigh_rotor_joint" type="fixed">
|
||||||
<origin rpy="0 0 0" xyz="${thigh_rotor_offset_x} ${thigh_rotor_offset_y*mirror} 0"/>
|
<origin rpy="0 0 0" xyz="${thigh_rotor_offset_x} ${thigh_rotor_offset_y*mirror} 0"/>
|
||||||
<parent link="${name}_hip"/>
|
<parent link="${name}_hip"/>
|
||||||
<child link="${name}_thigh_rotor"/>
|
<child link="${name}_thigh_rotor"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="${name}_thigh">
|
<link name="${name}_thigh">
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<xacro:if value="${mirror_dae == True}">
|
<xacro:if value="${mirror_dae == True}">
|
||||||
<mesh filename="file://$(find go1_description)/meshes/thigh.dae" scale="1 1 1"/>
|
<mesh filename="file://$(find go1_description)/meshes/thigh.dae" scale="1 1 1"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<xacro:if value="${mirror_dae == False}">
|
<xacro:if value="${mirror_dae == False}">
|
||||||
<mesh filename="file://$(find go1_description)/meshes/thigh_mirror.dae" scale="1 1 1"/>
|
<mesh filename="file://$(find go1_description)/meshes/thigh_mirror.dae" scale="1 1 1"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="grey"/>
|
<material name="grey"/>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 ${-thigh_length/2.0}"/>
|
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 ${-thigh_length/2.0}"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="${thigh_length} ${thigh_width} ${thigh_height}"/>
|
<box size="${thigh_length} ${thigh_width} ${thigh_height}"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin rpy="0 0 0" xyz="${thigh_com_x} ${thigh_com_y*mirror} ${thigh_com_z}"/>
|
<origin rpy="0 0 0" xyz="${thigh_com_x} ${thigh_com_y*mirror} ${thigh_com_z}"/>
|
||||||
<mass value="${thigh_mass}"/>
|
<mass value="${thigh_mass}"/>
|
||||||
<inertia
|
<inertia
|
||||||
ixx="${thigh_ixx}" ixy="${thigh_ixy*mirror}" ixz="${thigh_ixz}"
|
ixx="${thigh_ixx}" ixy="${thigh_ixy*mirror}" ixz="${thigh_ixz}"
|
||||||
iyy="${thigh_iyy}" iyz="${thigh_iyz*mirror}"
|
iyy="${thigh_iyy}" iyz="${thigh_iyz*mirror}"
|
||||||
izz="${thigh_izz}"/>
|
izz="${thigh_izz}"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link name="${name}_thigh_rotor">
|
<link name="${name}_thigh_rotor">
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<cylinder length="0.02" radius="0.035"/>
|
<cylinder length="0.02" radius="0.035"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</visual>
|
</visual>
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin rpy="0 0 0" xyz="${thigh_rotor_com_x} ${thigh_rotor_com_y} ${thigh_rotor_com_z}"/>
|
<origin rpy="0 0 0" xyz="${thigh_rotor_com_x} ${thigh_rotor_com_y} ${thigh_rotor_com_z}"/>
|
||||||
<mass value="${thigh_rotor_mass}"/>
|
<mass value="${thigh_rotor_mass}"/>
|
||||||
<inertia
|
<inertia
|
||||||
ixx="${thigh_rotor_ixx}" ixy="${thigh_rotor_ixy}" ixz="${thigh_rotor_ixz}"
|
ixx="${thigh_rotor_ixx}" ixy="${thigh_rotor_ixy}" ixz="${thigh_rotor_ixz}"
|
||||||
iyy="${thigh_rotor_iyy}" iyz="${thigh_rotor_iyz}"
|
iyy="${thigh_rotor_iyy}" iyz="${thigh_rotor_iyz}"
|
||||||
izz="${thigh_rotor_izz}"/>
|
izz="${thigh_rotor_izz}"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="${name}_calf_joint" type="revolute">
|
<joint name="${name}_calf_joint" type="revolute">
|
||||||
<origin rpy="0 0 0" xyz="0 0 ${-thigh_length}"/>
|
<origin rpy="0 0 0" xyz="0 0 ${-thigh_length}"/>
|
||||||
<parent link="${name}_thigh"/>
|
<parent link="${name}_thigh"/>
|
||||||
<child link="${name}_calf"/>
|
<child link="${name}_calf"/>
|
||||||
<axis xyz="0 1 0"/>
|
<axis xyz="0 1 0"/>
|
||||||
<dynamics damping="${damping}" friction="${friction}"/>
|
<dynamics damping="${damping}" friction="${friction}"/>
|
||||||
<limit effort="${calf_torque_max}" velocity="${calf_velocity_max}" lower="${calf_position_min}"
|
<limit effort="${calf_torque_max}" velocity="${calf_velocity_max}" lower="${calf_position_min}"
|
||||||
upper="${calf_position_max}"/>
|
upper="${calf_position_max}"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="${name}_calf_rotor_joint" type="fixed">
|
<joint name="${name}_calf_rotor_joint" type="fixed">
|
||||||
<origin rpy="0 0 0" xyz="${calf_rotor_offset_x} ${calf_rotor_offset_y*mirror} 0"/>
|
<origin rpy="0 0 0" xyz="${calf_rotor_offset_x} ${calf_rotor_offset_y*mirror} 0"/>
|
||||||
<parent link="${name}_thigh"/>
|
<parent link="${name}_thigh"/>
|
||||||
<child link="${name}_calf_rotor"/>
|
<child link="${name}_calf_rotor"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="${name}_calf">
|
<link name="${name}_calf">
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="file://$(find go1_description)/meshes/calf.dae" scale="1 1 1"/>
|
<mesh filename="file://$(find go1_description)/meshes/calf.dae" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="light-grey"/>
|
<material name="light-grey"/>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 ${-calf_length/2.0}"/>
|
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 ${-calf_length/2.0}"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="${calf_length} ${calf_width} ${calf_height}"/>
|
<box size="${calf_length} ${calf_width} ${calf_height}"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin rpy="0 0 0" xyz="${calf_com_x} ${calf_com_y} ${calf_com_z}"/>
|
<origin rpy="0 0 0" xyz="${calf_com_x} ${calf_com_y} ${calf_com_z}"/>
|
||||||
<mass value="${calf_mass}"/>
|
<mass value="${calf_mass}"/>
|
||||||
<inertia
|
<inertia
|
||||||
ixx="${calf_ixx}" ixy="${calf_ixy}" ixz="${calf_ixz}"
|
ixx="${calf_ixx}" ixy="${calf_ixy}" ixz="${calf_ixz}"
|
||||||
iyy="${calf_iyy}" iyz="${calf_iyz}"
|
iyy="${calf_iyy}" iyz="${calf_iyz}"
|
||||||
izz="${calf_izz}"/>
|
izz="${calf_izz}"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link name="${name}_calf_rotor">
|
<link name="${name}_calf_rotor">
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<cylinder length="0.02" radius="0.035"/>
|
<cylinder length="0.02" radius="0.035"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</visual>
|
</visual>
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin rpy="0 0 0" xyz="${calf_rotor_com_x} ${calf_rotor_com_y} ${calf_rotor_com_z}"/>
|
<origin rpy="0 0 0" xyz="${calf_rotor_com_x} ${calf_rotor_com_y} ${calf_rotor_com_z}"/>
|
||||||
<mass value="${calf_rotor_mass}"/>
|
<mass value="${calf_rotor_mass}"/>
|
||||||
<inertia
|
<inertia
|
||||||
ixx="${calf_rotor_ixx}" ixy="${calf_rotor_ixy}" ixz="${calf_rotor_ixz}"
|
ixx="${calf_rotor_ixx}" ixy="${calf_rotor_ixy}" ixz="${calf_rotor_ixz}"
|
||||||
iyy="${calf_rotor_iyy}" iyz="${calf_rotor_iyz}"
|
iyy="${calf_rotor_iyy}" iyz="${calf_rotor_iyz}"
|
||||||
izz="${calf_rotor_izz}"/>
|
izz="${calf_rotor_izz}"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="${name}_foot_fixed" type="fixed">
|
<joint name="${name}_foot_fixed" type="fixed">
|
||||||
<origin rpy="0 0 0" xyz="0 0 ${-(calf_length)}"/>
|
<origin rpy="0 0 0" xyz="0 0 ${-(calf_length)}"/>
|
||||||
<parent link="${name}_calf"/>
|
<parent link="${name}_calf"/>
|
||||||
<child link="${name}_foot"/>
|
<child link="${name}_foot"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="${name}_foot">
|
<link name="${name}_foot">
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<sphere radius="${foot_radius-0.01}"/>
|
<sphere radius="${foot_radius-0.01}"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<sphere radius="${foot_radius}"/>
|
<sphere radius="${foot_radius}"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="${foot_mass}"/>
|
<mass value="${foot_mass}"/>
|
||||||
<inertia
|
<inertia
|
||||||
ixx="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}" ixy="0.0" ixz="0.0"
|
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"
|
iyy="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}" iyz="0.0"
|
||||||
izz="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}"/>
|
izz="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<gazebo reference="{name}_hip">
|
<gazebo reference="{name}_hip">
|
||||||
<mu1>0.2</mu1>
|
<mu1>0.2</mu1>
|
||||||
<mu2>0.2</mu2>
|
<mu2>0.2</mu2>
|
||||||
</gazebo>
|
</gazebo>
|
||||||
|
|
||||||
<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>
|
||||||
|
|
||||||
<gazebo reference="{name}_foot">
|
<gazebo reference="{name}_foot">
|
||||||
<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>
|
||||||
<kp value="1000000.0"/>
|
<kp value="1000000.0"/>
|
||||||
<kd value="1.0"/>
|
<kd value="1.0"/>
|
||||||
</gazebo>
|
</gazebo>
|
||||||
|
|
||||||
<xacro:leg_transmission name="${name}"/>
|
<xacro:leg_transmission name="${name}"/>
|
||||||
</xacro:macro>
|
</xacro:macro>
|
||||||
</robot>
|
</robot>
|
||||||
|
|
|
@ -1,48 +1,48 @@
|
||||||
<?xml version="1.0"?>
|
<?xml version="1.0"?>
|
||||||
<robot>
|
<robot>
|
||||||
|
|
||||||
<material name="black">
|
<material name="black">
|
||||||
<color rgba="0.0 0.0 0.0 1.0"/>
|
<color rgba="0.0 0.0 0.0 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<material name="blue">
|
<material name="blue">
|
||||||
<color rgba="0.0 0.0 0.8 1.0"/>
|
<color rgba="0.0 0.0 0.8 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<material name="green">
|
<material name="green">
|
||||||
<color rgba="0.0 0.8 0.0 1.0"/>
|
<color rgba="0.0 0.8 0.0 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<material name="deep-grey">
|
<material name="deep-grey">
|
||||||
<color rgba="0.1 0.1 0.1 1.0"/>
|
<color rgba="0.1 0.1 0.1 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<material name="grey">
|
<material name="grey">
|
||||||
<color rgba="0.2 0.2 0.2 1.0"/>
|
<color rgba="0.2 0.2 0.2 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<material name="light-grey">
|
<material name="light-grey">
|
||||||
<color rgba="0.35 0.35 0.35 1.0"/>
|
<color rgba="0.35 0.35 0.35 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<material name="silver">
|
<material name="silver">
|
||||||
<color rgba="${233/255} ${233/255} ${216/255} 1.0"/>
|
<color rgba="${233/255} ${233/255} ${216/255} 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<material name="orange">
|
<material name="orange">
|
||||||
<color rgba="${255/255} ${108/255} ${10/255} 1.0"/>
|
<color rgba="${255/255} ${108/255} ${10/255} 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<material name="brown">
|
<material name="brown">
|
||||||
<color rgba="${222/255} ${207/255} ${195/255} 1.0"/>
|
<color rgba="${222/255} ${207/255} ${195/255} 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<material name="red">
|
<material name="red">
|
||||||
<color rgba="0.8 0.0 0.0 1.0"/>
|
<color rgba="0.8 0.0 0.0 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<material name="white">
|
<material name="white">
|
||||||
<color rgba="1.0 1.0 1.0 1.0"/>
|
<color rgba="1.0 1.0 1.0 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
</robot>
|
</robot>
|
||||||
|
|
|
@ -2,157 +2,163 @@
|
||||||
|
|
||||||
<robot name="go1" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
<robot name="go1" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
<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"/>
|
||||||
<xacro:include filename="$(find go1_description)/xacro/leg.xacro"/>
|
<xacro:include filename="$(find go1_description)/xacro/leg.xacro"/>
|
||||||
|
|
||||||
<xacro:include filename="$(find go1_description)/xacro/depthCamera.xacro"/>
|
<xacro:include filename="$(find go1_description)/xacro/depthCamera.xacro"/>
|
||||||
<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:include filename="$(find go1_description)/xacro/gazebo.xacro"/>
|
<xacro:if value="$(arg CLASSIC)">
|
||||||
</xacro:if>
|
<xacro:include filename="$(find go1_description)/xacro/gazebo_classic.xacro"/>
|
||||||
<xacro:unless value="$(arg GAZEBO)">
|
</xacro:if>
|
||||||
<xacro:include filename="$(find go1_description)/xacro/ros2_control.xacro"/>
|
<xacro:unless value="$(arg CLASSIC)">
|
||||||
</xacro:unless>
|
<xacro:include filename="$(find go1_description)/xacro/gazebo.xacro"/>
|
||||||
|
</xacro:unless>
|
||||||
|
</xacro:if>
|
||||||
|
<xacro:unless value="$(arg GAZEBO)">
|
||||||
|
<xacro:include filename="$(find go1_description)/xacro/ros2_control.xacro"/>
|
||||||
|
</xacro:unless>
|
||||||
|
|
||||||
|
|
||||||
<!-- <xacro:stairs stairs="15" xpos="0" ypos="0" zpos="0" /> -->
|
<!-- <xacro:stairs stairs="15" xpos="0" ypos="0" zpos="0" /> -->
|
||||||
|
|
||||||
<!-- Rotor related joint and link is only for demonstrate location. -->
|
<!-- Rotor related joint and link is only for demonstrate location. -->
|
||||||
<!-- Actually, the rotor will rotate and the joint is not fixed. Reduction ratio should be considered. -->
|
<!-- Actually, the rotor will rotate and the joint is not fixed. Reduction ratio should be considered. -->
|
||||||
|
|
||||||
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
|
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
|
||||||
<xacro:if value="$(arg DEBUG)">
|
<xacro:if value="$(arg DEBUG)">
|
||||||
<link name="world"/>
|
<link name="world"/>
|
||||||
<joint name="base_static_joint" type="fixed">
|
<joint name="base_static_joint" type="fixed">
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<parent link="world"/>
|
<parent link="world"/>
|
||||||
<child link="base"/>
|
<child link="base"/>
|
||||||
</joint>
|
</joint>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
|
|
||||||
<link name="base">
|
<link name="base">
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.001 0.001 0.001"/>
|
<box size="0.001 0.001 0.001"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</visual>
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="floating_base" type="fixed">
|
<joint name="floating_base" type="fixed">
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<parent link="base"/>
|
<parent link="base"/>
|
||||||
<child link="trunk"/>
|
<child link="trunk"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="trunk">
|
<link name="trunk">
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="file://$(find go1_description)/meshes/trunk.dae" scale="1 1 1"/>
|
<mesh filename="file://$(find go1_description)/meshes/trunk.dae" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="light-grey"/>
|
<material name="light-grey"/>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="${trunk_length} ${trunk_width} ${trunk_height}"/>
|
<box size="${trunk_length} ${trunk_width} ${trunk_height}"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</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}"/>
|
||||||
<inertia
|
<inertia
|
||||||
ixx="${trunk_ixx}" ixy="${trunk_ixy}" ixz="${trunk_ixz}"
|
ixx="${trunk_ixx}" ixy="${trunk_ixy}" ixz="${trunk_ixz}"
|
||||||
iyy="${trunk_iyy}" iyz="${trunk_iyz}"
|
iyy="${trunk_iyy}" iyz="${trunk_iyz}"
|
||||||
izz="${trunk_izz}"/>
|
izz="${trunk_izz}"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="imu_joint" type="fixed">
|
<joint name="imu_joint" type="fixed">
|
||||||
<parent link="trunk"/>
|
<parent link="trunk"/>
|
||||||
<child link="imu_link"/>
|
<child link="imu_link"/>
|
||||||
<origin rpy="0 0 0" xyz="-0.01592 -0.06659 -0.00617"/>
|
<origin rpy="0 0 0" xyz="-0.01592 -0.06659 -0.00617"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="imu_link">
|
<link name="imu_link">
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="0.001"/>
|
<mass value="0.001"/>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<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"/>
|
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.001 0.001 0.001"/>
|
<box size="0.001 0.001 0.001"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<!-- <material name="red"/> -->
|
<!-- <material name="red"/> -->
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size=".001 .001 .001"/>
|
<box size=".001 .001 .001"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<xacro:leg name="FR" mirror="-1" mirror_dae= "False" front_hind="1" front_hind_dae="True" />
|
<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="FL" mirror="1" mirror_dae="True" front_hind="1" front_hind_dae="True"/>
|
||||||
<xacro:leg name="RR" mirror="-1" mirror_dae="False" front_hind="-1" front_hind_dae="False" />
|
<xacro:leg name="RR" mirror="-1" mirror_dae="False" front_hind="-1" front_hind_dae="False"/>
|
||||||
<xacro:leg name="RL" mirror="1" mirror_dae="True" front_hind="-1" front_hind_dae="False" />
|
<xacro:leg name="RL" mirror="1" mirror_dae="True" front_hind="-1" front_hind_dae="False"/>
|
||||||
|
|
||||||
<xacro:depthCamera camID="1" name="face">
|
<xacro:depthCamera camID="1" name="face">
|
||||||
<origin rpy="${PI} 0 0" xyz="0.2785 0.0125 0.0167"/>
|
<origin rpy="${PI} 0 0" xyz="0.2785 0.0125 0.0167"/>
|
||||||
</xacro:depthCamera>
|
</xacro:depthCamera>
|
||||||
|
|
||||||
<xacro:depthCamera camID="2" name="chin">
|
<xacro:depthCamera camID="2" name="chin">
|
||||||
<origin rpy="${PI} ${PI/2} 0" xyz="0.2522 0.0125 -0.0436"/>
|
<origin rpy="${PI} ${PI/2} 0" xyz="0.2522 0.0125 -0.0436"/>
|
||||||
</xacro:depthCamera>
|
</xacro:depthCamera>
|
||||||
|
|
||||||
<xacro:depthCamera camID="3" name="left">
|
<xacro:depthCamera camID="3" name="left">
|
||||||
<origin rpy="${PI} 0.2618 ${PI/2}" xyz="-0.066 0.082 -0.0176"/>
|
<origin rpy="${PI} 0.2618 ${PI/2}" xyz="-0.066 0.082 -0.0176"/>
|
||||||
</xacro:depthCamera>
|
</xacro:depthCamera>
|
||||||
|
|
||||||
<xacro:depthCamera camID="4" name="right">
|
<xacro:depthCamera camID="4" name="right">
|
||||||
<origin rpy="${PI} 0.2618 ${-PI/2}" xyz="-0.041 -0.082 -0.0176"/>
|
<origin rpy="${PI} 0.2618 ${-PI/2}" xyz="-0.041 -0.082 -0.0176"/>
|
||||||
</xacro:depthCamera>
|
</xacro:depthCamera>
|
||||||
|
|
||||||
<xacro:depthCamera camID="5" name="rearDown">
|
<xacro:depthCamera camID="5" name="rearDown">
|
||||||
<origin rpy="${PI} ${PI/2} 0" xyz="-0.0825 0.0125 -0.04365"/>
|
<origin rpy="${PI} ${PI/2} 0" xyz="-0.0825 0.0125 -0.04365"/>
|
||||||
</xacro:depthCamera>
|
</xacro:depthCamera>
|
||||||
|
|
||||||
<joint name="camera_laserscan_joint_left" type="fixed">
|
<joint name="camera_laserscan_joint_left" type="fixed">
|
||||||
<origin rpy="0 0.2618 0" xyz="0 0 0"/>
|
<origin rpy="0 0.2618 0" xyz="0 0 0"/>
|
||||||
<parent link="camera_left"/>
|
<parent link="camera_left"/>
|
||||||
<child link="camera_laserscan_link_left"/>
|
<child link="camera_laserscan_link_left"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="camera_laserscan_link_left">
|
<link name="camera_laserscan_link_left">
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="camera_laserscan_joint_right" type="fixed">
|
<joint name="camera_laserscan_joint_right" type="fixed">
|
||||||
<origin rpy="0 0.2618 0" xyz="0 0 0"/>
|
<origin rpy="0 0.2618 0" xyz="0 0 0"/>
|
||||||
<parent link="camera_right"/>
|
<parent link="camera_right"/>
|
||||||
<child link="camera_laserscan_link_right"/>
|
<child link="camera_laserscan_link_right"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="camera_laserscan_link_right">
|
<link name="camera_laserscan_link_right">
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<xacro:ultraSound name="left">
|
<xacro:ultraSound name="left">
|
||||||
<origin rpy="0 0.2618 ${PI/2}" xyz="-0.0535 0.0826 0.00868"/>
|
<origin rpy="0 0.2618 ${PI/2}" xyz="-0.0535 0.0826 0.00868"/>
|
||||||
</xacro:ultraSound>
|
</xacro:ultraSound>
|
||||||
|
|
||||||
<xacro:ultraSound name="right">
|
<xacro:ultraSound name="right">
|
||||||
<origin rpy="0 0.2618 ${-PI/2}" xyz="-0.0535 -0.0826 0.00868"/>
|
<origin rpy="0 0.2618 ${-PI/2}" xyz="-0.0535 -0.0826 0.00868"/>
|
||||||
</xacro:ultraSound>
|
</xacro:ultraSound>
|
||||||
|
|
||||||
<xacro:ultraSound name="face">
|
<xacro:ultraSound name="face">
|
||||||
<origin rpy="0 0 0" xyz="0.2747 0.0 -0.0088"/>
|
<origin rpy="0 0 0" xyz="0.2747 0.0 -0.0088"/>
|
||||||
</xacro:ultraSound>
|
</xacro:ultraSound>
|
||||||
</robot>
|
</robot>
|
||||||
|
|
|
@ -1,176 +1,176 @@
|
||||||
<?xml version="1.0"?>
|
<?xml version="1.0"?>
|
||||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
<ros2_control name="UnitreeSystem" type="system">
|
<ros2_control name="UnitreeSystem" type="system">
|
||||||
|
|
||||||
<hardware>
|
<hardware>
|
||||||
<plugin>hardware_unitree_mujoco/HardwareUnitree</plugin>
|
<plugin>hardware_unitree_mujoco/HardwareUnitree</plugin>
|
||||||
</hardware>
|
</hardware>
|
||||||
|
|
||||||
<joint name="FR_hip_joint">
|
<joint name="FR_hip_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FR_thigh_joint">
|
<joint name="FR_thigh_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FR_calf_joint">
|
<joint name="FR_calf_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FL_hip_joint">
|
<joint name="FL_hip_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FL_thigh_joint">
|
<joint name="FL_thigh_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FL_calf_joint">
|
<joint name="FL_calf_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RR_hip_joint">
|
<joint name="RR_hip_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RR_thigh_joint">
|
<joint name="RR_thigh_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RR_calf_joint">
|
<joint name="RR_calf_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RL_hip_joint">
|
<joint name="RL_hip_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RL_thigh_joint">
|
<joint name="RL_thigh_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RL_calf_joint">
|
<joint name="RL_calf_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<sensor name="imu_sensor">
|
<sensor name="imu_sensor">
|
||||||
<state_interface name="orientation.w"/>
|
<state_interface name="orientation.w"/>
|
||||||
<state_interface name="orientation.x"/>
|
<state_interface name="orientation.x"/>
|
||||||
<state_interface name="orientation.y"/>
|
<state_interface name="orientation.y"/>
|
||||||
<state_interface name="orientation.z"/>
|
<state_interface name="orientation.z"/>
|
||||||
<state_interface name="angular_velocity.x"/>
|
<state_interface name="angular_velocity.x"/>
|
||||||
<state_interface name="angular_velocity.y"/>
|
<state_interface name="angular_velocity.y"/>
|
||||||
<state_interface name="angular_velocity.z"/>
|
<state_interface name="angular_velocity.z"/>
|
||||||
<state_interface name="linear_acceleration.x"/>
|
<state_interface name="linear_acceleration.x"/>
|
||||||
<state_interface name="linear_acceleration.y"/>
|
<state_interface name="linear_acceleration.y"/>
|
||||||
<state_interface name="linear_acceleration.z"/>
|
<state_interface name="linear_acceleration.z"/>
|
||||||
</sensor>
|
</sensor>
|
||||||
|
|
||||||
<sensor name="foot_force">
|
<sensor name="foot_force">
|
||||||
<state_interface name="FR"/>
|
<state_interface name="FR"/>
|
||||||
<state_interface name="FL"/>
|
<state_interface name="FL"/>
|
||||||
<state_interface name="RR"/>
|
<state_interface name="RR"/>
|
||||||
<state_interface name="RL"/>
|
<state_interface name="RL"/>
|
||||||
</sensor>
|
</sensor>
|
||||||
|
|
||||||
</ros2_control>
|
</ros2_control>
|
||||||
|
|
||||||
</robot>
|
</robot>
|
||||||
|
|
|
@ -2,41 +2,41 @@
|
||||||
|
|
||||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
<xacro:macro name="leg_transmission" params="name">
|
<xacro:macro name="leg_transmission" params="name">
|
||||||
|
|
||||||
<transmission name="${name}_hip_tran">
|
<transmission name="${name}_hip_tran">
|
||||||
<type>transmission_interface/SimpleTransmission</type>
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
<joint name="${name}_hip_joint">
|
<joint name="${name}_hip_joint">
|
||||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||||
</joint>
|
</joint>
|
||||||
<actuator name="${name}_hip_motor">
|
<actuator name="${name}_hip_motor">
|
||||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||||
<mechanicalReduction>1</mechanicalReduction>
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
</actuator>
|
</actuator>
|
||||||
</transmission>
|
</transmission>
|
||||||
|
|
||||||
<transmission name="${name}_thigh_tran">
|
<transmission name="${name}_thigh_tran">
|
||||||
<type>transmission_interface/SimpleTransmission</type>
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
<joint name="${name}_thigh_joint">
|
<joint name="${name}_thigh_joint">
|
||||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||||
</joint>
|
</joint>
|
||||||
<actuator name="${name}_thigh_motor">
|
<actuator name="${name}_thigh_motor">
|
||||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||||
<mechanicalReduction>1</mechanicalReduction>
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
</actuator>
|
</actuator>
|
||||||
</transmission>
|
</transmission>
|
||||||
|
|
||||||
<transmission name="${name}_calf_tran">
|
<transmission name="${name}_calf_tran">
|
||||||
<type>transmission_interface/SimpleTransmission</type>
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
<joint name="${name}_calf_joint">
|
<joint name="${name}_calf_joint">
|
||||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||||
</joint>
|
</joint>
|
||||||
<actuator name="${name}_calf_motor">
|
<actuator name="${name}_calf_motor">
|
||||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||||
<mechanicalReduction>1</mechanicalReduction>
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
</actuator>
|
</actuator>
|
||||||
</transmission>
|
</transmission>
|
||||||
|
|
||||||
</xacro:macro>
|
</xacro:macro>
|
||||||
|
|
||||||
</robot>
|
</robot>
|
||||||
|
|
|
@ -1,33 +1,33 @@
|
||||||
<?xml version="1.0"?>
|
<?xml version="1.0"?>
|
||||||
|
|
||||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
<xacro:macro name="ultraSound" params="name *origin">
|
<xacro:macro name="ultraSound" params="name *origin">
|
||||||
<joint name="ultraSound_joint_${name}" type="fixed">
|
<joint name="ultraSound_joint_${name}" type="fixed">
|
||||||
<xacro:insert_block name="origin"/>
|
<xacro:insert_block name="origin"/>
|
||||||
<parent link="trunk"/>
|
<parent link="trunk"/>
|
||||||
<child link="ultraSound_${name}"/>
|
<child link="ultraSound_${name}"/>
|
||||||
</joint>
|
</joint>
|
||||||
<link name="ultraSound_${name}">
|
<link name="ultraSound_${name}">
|
||||||
<collision>
|
<collision>
|
||||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size=".001 .001 .001"/>
|
<box size=".001 .001 .001"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
|
|
||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="file://$(find go1_description)/meshes/ultraSound.dae" scale="1 1 1"/>
|
<mesh filename="file://$(find go1_description)/meshes/ultraSound.dae" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="black"/>
|
<material name="black"/>
|
||||||
</visual>
|
</visual>
|
||||||
|
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="1e-5" />
|
<mass value="1e-5"/>
|
||||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
|
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
</xacro:macro>
|
</xacro:macro>
|
||||||
</robot>
|
</robot>
|
|
@ -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
|
||||||
|
|
|
@ -2,120 +2,120 @@
|
||||||
|
|
||||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
<!-- Constants for robot dimensions -->
|
<!-- Constants for robot dimensions -->
|
||||||
<xacro:property name="PI" value="3.1415926535897931"/>
|
<xacro:property name="PI" value="3.1415926535897931"/>
|
||||||
<xacro:property name="stick_mass" value="0.00001"/>
|
<xacro:property name="stick_mass" value="0.00001"/>
|
||||||
|
|
||||||
<!-- simplified collision value -->
|
<!-- simplified collision value -->
|
||||||
<xacro:property name="trunk_width" value="0.0935"/>
|
<xacro:property name="trunk_width" value="0.0935"/>
|
||||||
<xacro:property name="trunk_length" value="0.3762"/>
|
<xacro:property name="trunk_length" value="0.3762"/>
|
||||||
<xacro:property name="trunk_height" value="0.114"/>
|
<xacro:property name="trunk_height" value="0.114"/>
|
||||||
<xacro:property name="hip_radius" value="0.046"/>
|
<xacro:property name="hip_radius" value="0.046"/>
|
||||||
<xacro:property name="hip_length" value="0.04"/>
|
<xacro:property name="hip_length" value="0.04"/>
|
||||||
<xacro:property name="thigh_shoulder_radius" value="0.041"/>
|
<xacro:property name="thigh_shoulder_radius" value="0.041"/>
|
||||||
<xacro:property name="thigh_shoulder_length" value="0.032"/>
|
<xacro:property name="thigh_shoulder_length" value="0.032"/>
|
||||||
<xacro:property name="thigh_width" value="0.0245"/>
|
<xacro:property name="thigh_width" value="0.0245"/>
|
||||||
<xacro:property name="thigh_height" value="0.034"/>
|
<xacro:property name="thigh_height" value="0.034"/>
|
||||||
<xacro:property name="calf_width" value="0.016"/>
|
<xacro:property name="calf_width" value="0.016"/>
|
||||||
<xacro:property name="calf_height" value="0.016"/>
|
<xacro:property name="calf_height" value="0.016"/>
|
||||||
<xacro:property name="foot_radius" value="0.02"/>
|
<xacro:property name="foot_radius" value="0.02"/>
|
||||||
<xacro:property name="stick_radius" value="0.01"/>
|
<xacro:property name="stick_radius" value="0.01"/>
|
||||||
<xacro:property name="stick_length" value="0.2"/>
|
<xacro:property name="stick_length" value="0.2"/>
|
||||||
|
|
||||||
<!-- kinematic value -->
|
<!-- kinematic value -->
|
||||||
<xacro:property name="thigh_offset" value="0.0955"/>
|
<xacro:property name="thigh_offset" value="0.0955"/>
|
||||||
<xacro:property name="thigh_length" value="0.213"/>
|
<xacro:property name="thigh_length" value="0.213"/>
|
||||||
<xacro:property name="calf_length" value="0.213"/>
|
<xacro:property name="calf_length" value="0.213"/>
|
||||||
|
|
||||||
<!-- leg offset from trunk center value -->
|
<!-- leg offset from trunk center value -->
|
||||||
<xacro:property name="leg_offset_x" value="0.1934"/>
|
<xacro:property name="leg_offset_x" value="0.1934"/>
|
||||||
<xacro:property name="leg_offset_y" value="0.0465"/>
|
<xacro:property name="leg_offset_y" value="0.0465"/>
|
||||||
<!-- <xacro:property name="trunk_offset_z" value="0.01675"/> -->
|
<!-- <xacro:property name="trunk_offset_z" value="0.01675"/> -->
|
||||||
<xacro:property name="hip_offset" value="0.0955"/>
|
<xacro:property name="hip_offset" value="0.0955"/>
|
||||||
|
|
||||||
<!-- offset of link locations (left front) -->
|
<!-- offset of link locations (left front) -->
|
||||||
<xacro:property name="hip_offset_x" value="0.1934"/>
|
<xacro:property name="hip_offset_x" value="0.1934"/>
|
||||||
<xacro:property name="hip_offset_y" value="0.0465"/>
|
<xacro:property name="hip_offset_y" value="0.0465"/>
|
||||||
<xacro:property name="hip_offset_z" value="0.0"/>
|
<xacro:property name="hip_offset_z" value="0.0"/>
|
||||||
|
|
||||||
|
|
||||||
<xacro:property name="thigh_offset_x" value="0"/>
|
<xacro:property name="thigh_offset_x" value="0"/>
|
||||||
<xacro:property name="thigh_offset_y" value="0.0955"/>
|
<xacro:property name="thigh_offset_y" value="0.0955"/>
|
||||||
<xacro:property name="thigh_offset_z" value="0.0"/>
|
<xacro:property name="thigh_offset_z" value="0.0"/>
|
||||||
|
|
||||||
|
|
||||||
<xacro:property name="calf_offset_x" value="0.0"/>
|
<xacro:property name="calf_offset_x" value="0.0"/>
|
||||||
<xacro:property name="calf_offset_y" value="0.0"/>
|
<xacro:property name="calf_offset_y" value="0.0"/>
|
||||||
<xacro:property name="calf_offset_z" value="-0.213"/>
|
<xacro:property name="calf_offset_z" value="-0.213"/>
|
||||||
|
|
||||||
|
|
||||||
<!-- joint limits -->
|
<!-- joint limits -->
|
||||||
<xacro:property name="damping" value="0.0"/>
|
<xacro:property name="damping" value="0.0"/>
|
||||||
<xacro:property name="friction" value="0.0"/>
|
<xacro:property name="friction" value="0.0"/>
|
||||||
<xacro:property name="hip_position_max" value="1.0472"/>
|
<xacro:property name="hip_position_max" value="1.0472"/>
|
||||||
<xacro:property name="hip_position_min" value="-1.0472"/>
|
<xacro:property name="hip_position_min" value="-1.0472"/>
|
||||||
<xacro:property name="hip_velocity_max" value="30.1"/>
|
<xacro:property name="hip_velocity_max" value="30.1"/>
|
||||||
<xacro:property name="hip_torque_max" value="23.7"/>
|
<xacro:property name="hip_torque_max" value="23.7"/>
|
||||||
<xacro:property name="thigh_position_max" value="3.4907"/>
|
<xacro:property name="thigh_position_max" value="3.4907"/>
|
||||||
<xacro:property name="thigh_position_min" value="-1.5708"/>
|
<xacro:property name="thigh_position_min" value="-1.5708"/>
|
||||||
<xacro:property name="thigh_velocity_max" value="30.1"/>
|
<xacro:property name="thigh_velocity_max" value="30.1"/>
|
||||||
<xacro:property name="thigh_torque_max" value="23.7"/>
|
<xacro:property name="thigh_torque_max" value="23.7"/>
|
||||||
<xacro:property name="calf_position_max" value="-0.83776"/>
|
<xacro:property name="calf_position_max" value="-0.83776"/>
|
||||||
<xacro:property name="calf_position_min" value="-2.7227"/>
|
<xacro:property name="calf_position_min" value="-2.7227"/>
|
||||||
<xacro:property name="calf_velocity_max" value="20.06"/>
|
<xacro:property name="calf_velocity_max" value="20.06"/>
|
||||||
<xacro:property name="calf_torque_max" value="35.55"/>
|
<xacro:property name="calf_torque_max" value="35.55"/>
|
||||||
|
|
||||||
<!-- dynamics inertial value -->
|
<!-- dynamics inertial value -->
|
||||||
<!-- trunk -->
|
<!-- trunk -->
|
||||||
<xacro:property name="trunk_mass" value="6.921"/>
|
<xacro:property name="trunk_mass" value="6.921"/>
|
||||||
<xacro:property name="trunk_com_x" value="0.021112"/>
|
<xacro:property name="trunk_com_x" value="0.021112"/>
|
||||||
<xacro:property name="trunk_com_y" value="0.00"/>
|
<xacro:property name="trunk_com_y" value="0.00"/>
|
||||||
<xacro:property name="trunk_com_z" value="-0.005366"/>
|
<xacro:property name="trunk_com_z" value="-0.005366"/>
|
||||||
<xacro:property name="trunk_ixx" value="0.02448"/>
|
<xacro:property name="trunk_ixx" value="0.02448"/>
|
||||||
<xacro:property name="trunk_ixy" value="0.00012166"/>
|
<xacro:property name="trunk_ixy" value="0.00012166"/>
|
||||||
<xacro:property name="trunk_ixz" value="0.0014849"/>
|
<xacro:property name="trunk_ixz" value="0.0014849"/>
|
||||||
<xacro:property name="trunk_iyy" value="0.098077"/>
|
<xacro:property name="trunk_iyy" value="0.098077"/>
|
||||||
<xacro:property name="trunk_iyz" value="-3.12E-05"/>
|
<xacro:property name="trunk_iyz" value="-3.12E-05"/>
|
||||||
<xacro:property name="trunk_izz" value="0.107"/>
|
<xacro:property name="trunk_izz" value="0.107"/>
|
||||||
|
|
||||||
<!-- hip (left front) -->
|
<!-- hip (left front) -->
|
||||||
<xacro:property name="hip_mass" value="0.678"/>
|
<xacro:property name="hip_mass" value="0.678"/>
|
||||||
<xacro:property name="hip_com_x" value="-0.0054"/>
|
<xacro:property name="hip_com_x" value="-0.0054"/>
|
||||||
<xacro:property name="hip_com_y" value="0.00194"/>
|
<xacro:property name="hip_com_y" value="0.00194"/>
|
||||||
<xacro:property name="hip_com_z" value="-0.000105"/>
|
<xacro:property name="hip_com_z" value="-0.000105"/>
|
||||||
<xacro:property name="hip_ixx" value="0.00048"/>
|
<xacro:property name="hip_ixx" value="0.00048"/>
|
||||||
<xacro:property name="hip_ixy" value="-3.01E-06"/>
|
<xacro:property name="hip_ixy" value="-3.01E-06"/>
|
||||||
<xacro:property name="hip_ixz" value="1.11E-06"/>
|
<xacro:property name="hip_ixz" value="1.11E-06"/>
|
||||||
<xacro:property name="hip_iyy" value="0.000884"/>
|
<xacro:property name="hip_iyy" value="0.000884"/>
|
||||||
<xacro:property name="hip_iyz" value="-1.42E-06"/>
|
<xacro:property name="hip_iyz" value="-1.42E-06"/>
|
||||||
<xacro:property name="hip_izz" value="0.000596"/>
|
<xacro:property name="hip_izz" value="0.000596"/>
|
||||||
|
|
||||||
<!-- thigh -->
|
<!-- thigh -->
|
||||||
<xacro:property name="thigh_mass" value="1.152"/>
|
<xacro:property name="thigh_mass" value="1.152"/>
|
||||||
<xacro:property name="thigh_com_x" value="-0.00374"/>
|
<xacro:property name="thigh_com_x" value="-0.00374"/>
|
||||||
<xacro:property name="thigh_com_y" value="-0.0223"/>
|
<xacro:property name="thigh_com_y" value="-0.0223"/>
|
||||||
<xacro:property name="thigh_com_z" value="-0.0327"/>
|
<xacro:property name="thigh_com_z" value="-0.0327"/>
|
||||||
<xacro:property name="thigh_ixx" value="0.00584"/>
|
<xacro:property name="thigh_ixx" value="0.00584"/>
|
||||||
<xacro:property name="thigh_ixy" value="8.72E-05"/>
|
<xacro:property name="thigh_ixy" value="8.72E-05"/>
|
||||||
<xacro:property name="thigh_ixz" value="-0.000289"/>
|
<xacro:property name="thigh_ixz" value="-0.000289"/>
|
||||||
<xacro:property name="thigh_iyy" value="0.0058"/>
|
<xacro:property name="thigh_iyy" value="0.0058"/>
|
||||||
<xacro:property name="thigh_iyz" value="0.000808"/>
|
<xacro:property name="thigh_iyz" value="0.000808"/>
|
||||||
<xacro:property name="thigh_izz" value="0.00103"/>
|
<xacro:property name="thigh_izz" value="0.00103"/>
|
||||||
|
|
||||||
<!-- calf -->
|
<!-- calf -->
|
||||||
<xacro:property name="calf_mass" value="0.154"/>
|
<xacro:property name="calf_mass" value="0.154"/>
|
||||||
<xacro:property name="calf_com_x" value="0.00548"/>
|
<xacro:property name="calf_com_x" value="0.00548"/>
|
||||||
<xacro:property name="calf_com_y" value="-0.000975"/>
|
<xacro:property name="calf_com_y" value="-0.000975"/>
|
||||||
<xacro:property name="calf_com_z" value="-0.115"/>
|
<xacro:property name="calf_com_z" value="-0.115"/>
|
||||||
<xacro:property name="calf_ixx" value="0.00108"/>
|
<xacro:property name="calf_ixx" value="0.00108"/>
|
||||||
<xacro:property name="calf_ixy" value="3.4E-07"/>
|
<xacro:property name="calf_ixy" value="3.4E-07"/>
|
||||||
<xacro:property name="calf_ixz" value="1.72E-05"/>
|
<xacro:property name="calf_ixz" value="1.72E-05"/>
|
||||||
<xacro:property name="calf_iyy" value="0.0011"/>
|
<xacro:property name="calf_iyy" value="0.0011"/>
|
||||||
<xacro:property name="calf_iyz" value="8.28E-06"/>
|
<xacro:property name="calf_iyz" value="8.28E-06"/>
|
||||||
<xacro:property name="calf_izz" value="3.29E-05"/>
|
<xacro:property name="calf_izz" value="3.29E-05"/>
|
||||||
|
|
||||||
|
|
||||||
<!-- foot -->
|
<!-- foot -->
|
||||||
<xacro:property name="foot_mass" value="0.06"/>
|
<xacro:property name="foot_mass" value="0.06"/>
|
||||||
|
|
||||||
</robot>
|
</robot>
|
||||||
|
|
|
@ -1,188 +1,188 @@
|
||||||
<?xml version="1.0"?>
|
<?xml version="1.0"?>
|
||||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
<ros2_control name="GazeboSystem" type="system">
|
<ros2_control name="GazeboSystem" type="system">
|
||||||
<hardware>
|
<hardware>
|
||||||
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
|
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
|
||||||
</hardware>
|
</hardware>
|
||||||
|
|
||||||
<joint name="FR_hip_joint">
|
<joint name="FR_hip_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FR_thigh_joint">
|
<joint name="FR_thigh_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FR_calf_joint">
|
<joint name="FR_calf_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FL_hip_joint">
|
<joint name="FL_hip_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FL_thigh_joint">
|
<joint name="FL_thigh_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FL_calf_joint">
|
<joint name="FL_calf_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RR_hip_joint">
|
<joint name="RR_hip_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RR_thigh_joint">
|
<joint name="RR_thigh_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RR_calf_joint">
|
<joint name="RR_calf_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RL_hip_joint">
|
<joint name="RL_hip_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RL_thigh_joint">
|
<joint name="RL_thigh_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RL_calf_joint">
|
<joint name="RL_calf_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<sensor name="imu_sensor">
|
<sensor name="imu_sensor">
|
||||||
<state_interface name="orientation.x"/>
|
<state_interface name="orientation.x"/>
|
||||||
<state_interface name="orientation.y"/>
|
<state_interface name="orientation.y"/>
|
||||||
<state_interface name="orientation.z"/>
|
<state_interface name="orientation.z"/>
|
||||||
<state_interface name="orientation.w"/>
|
<state_interface name="orientation.w"/>
|
||||||
<state_interface name="angular_velocity.x"/>
|
<state_interface name="angular_velocity.x"/>
|
||||||
<state_interface name="angular_velocity.y"/>
|
<state_interface name="angular_velocity.y"/>
|
||||||
<state_interface name="angular_velocity.z"/>
|
<state_interface name="angular_velocity.z"/>
|
||||||
<state_interface name="linear_acceleration.x"/>
|
<state_interface name="linear_acceleration.x"/>
|
||||||
<state_interface name="linear_acceleration.y"/>
|
<state_interface name="linear_acceleration.y"/>
|
||||||
<state_interface name="linear_acceleration.z"/>
|
<state_interface name="linear_acceleration.z"/>
|
||||||
</sensor>
|
</sensor>
|
||||||
</ros2_control>
|
</ros2_control>
|
||||||
|
|
||||||
<gazebo>
|
<gazebo>
|
||||||
<plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
|
<plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
|
||||||
<parameters>$(find go2_description)/config/gazebo.yaml</parameters>
|
<parameters>$(find go2_description)/config/gazebo.yaml</parameters>
|
||||||
</plugin>
|
</plugin>
|
||||||
<plugin filename="gz-sim-imu-system"
|
<plugin filename="gz-sim-imu-system"
|
||||||
name="gz::sim::systems::Imu">
|
name="gz::sim::systems::Imu">
|
||||||
</plugin>
|
</plugin>
|
||||||
</gazebo>
|
</gazebo>
|
||||||
|
|
||||||
<gazebo reference="trunk">
|
<gazebo reference="trunk">
|
||||||
<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>
|
||||||
</gazebo>
|
</gazebo>
|
||||||
|
|
||||||
<gazebo reference="imu_link">
|
<gazebo reference="imu_link">
|
||||||
<sensor name="imu_sensor" type="imu">
|
<sensor name="imu_sensor" type="imu">
|
||||||
<always_on>1</always_on>
|
<always_on>1</always_on>
|
||||||
<update_rate>500</update_rate>
|
<update_rate>500</update_rate>
|
||||||
<visualize>true</visualize>
|
<visualize>true</visualize>
|
||||||
<topic>imu</topic>
|
<topic>imu</topic>
|
||||||
<imu>
|
<imu>
|
||||||
<angular_velocity>
|
<angular_velocity>
|
||||||
<x>
|
<x>
|
||||||
<noise type="gaussian">
|
<noise type="gaussian">
|
||||||
<mean>0.0</mean>
|
<mean>0.0</mean>
|
||||||
<stddev>2e-4</stddev>
|
<stddev>2e-4</stddev>
|
||||||
<bias_mean>0.0000075</bias_mean>
|
<bias_mean>0.0000075</bias_mean>
|
||||||
<bias_stddev>0.0000008</bias_stddev>
|
<bias_stddev>0.0000008</bias_stddev>
|
||||||
</noise>
|
</noise>
|
||||||
</x>
|
</x>
|
||||||
<y>
|
<y>
|
||||||
<noise type="gaussian">
|
<noise type="gaussian">
|
||||||
<mean>0.0</mean>
|
<mean>0.0</mean>
|
||||||
<stddev>2e-4</stddev>
|
<stddev>2e-4</stddev>
|
||||||
<bias_mean>0.0000075</bias_mean>
|
<bias_mean>0.0000075</bias_mean>
|
||||||
<bias_stddev>0.0000008</bias_stddev>
|
<bias_stddev>0.0000008</bias_stddev>
|
||||||
</noise>
|
</noise>
|
||||||
</y>
|
</y>
|
||||||
<z>
|
<z>
|
||||||
<noise type="gaussian">
|
<noise type="gaussian">
|
||||||
<mean>0.0</mean>
|
<mean>0.0</mean>
|
||||||
<stddev>2e-4</stddev>
|
<stddev>2e-4</stddev>
|
||||||
<bias_mean>0.0000075</bias_mean>
|
<bias_mean>0.0000075</bias_mean>
|
||||||
<bias_stddev>0.0000008</bias_stddev>
|
<bias_stddev>0.0000008</bias_stddev>
|
||||||
</noise>
|
</noise>
|
||||||
</z>
|
</z>
|
||||||
</angular_velocity>
|
</angular_velocity>
|
||||||
<linear_acceleration>
|
<linear_acceleration>
|
||||||
<x>
|
<x>
|
||||||
<noise type="gaussian">
|
<noise type="gaussian">
|
||||||
<mean>0.0</mean>
|
<mean>0.0</mean>
|
||||||
<stddev>1.7e-2</stddev>
|
<stddev>1.7e-2</stddev>
|
||||||
<bias_mean>0.1</bias_mean>
|
<bias_mean>0.1</bias_mean>
|
||||||
<bias_stddev>0.001</bias_stddev>
|
<bias_stddev>0.001</bias_stddev>
|
||||||
</noise>
|
</noise>
|
||||||
</x>
|
</x>
|
||||||
<y>
|
<y>
|
||||||
<noise type="gaussian">
|
<noise type="gaussian">
|
||||||
<mean>0.0</mean>
|
<mean>0.0</mean>
|
||||||
<stddev>1.7e-2</stddev>
|
<stddev>1.7e-2</stddev>
|
||||||
<bias_mean>0.1</bias_mean>
|
<bias_mean>0.1</bias_mean>
|
||||||
<bias_stddev>0.001</bias_stddev>
|
<bias_stddev>0.001</bias_stddev>
|
||||||
</noise>
|
</noise>
|
||||||
</y>
|
</y>
|
||||||
<z>
|
<z>
|
||||||
<noise type="gaussian">
|
<noise type="gaussian">
|
||||||
<mean>0.0</mean>
|
<mean>0.0</mean>
|
||||||
<stddev>1.7e-2</stddev>
|
<stddev>1.7e-2</stddev>
|
||||||
<bias_mean>0.1</bias_mean>
|
<bias_mean>0.1</bias_mean>
|
||||||
<bias_stddev>0.001</bias_stddev>
|
<bias_stddev>0.001</bias_stddev>
|
||||||
</noise>
|
</noise>
|
||||||
</z>
|
</z>
|
||||||
</linear_acceleration>
|
</linear_acceleration>
|
||||||
</imu>
|
</imu>
|
||||||
</sensor>
|
</sensor>
|
||||||
</gazebo>
|
</gazebo>
|
||||||
<gazebo reference="imu_joint">
|
<gazebo reference="imu_joint">
|
||||||
<disableFixedJointLumping>true</disableFixedJointLumping>
|
<disableFixedJointLumping>true</disableFixedJointLumping>
|
||||||
</gazebo>
|
</gazebo>
|
||||||
|
|
||||||
</robot>
|
</robot>
|
||||||
|
|
|
@ -1,139 +1,139 @@
|
||||||
<?xml version="1.0"?>
|
<?xml version="1.0"?>
|
||||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
<ros2_control name="GazeboSystem" type="system">
|
<ros2_control name="GazeboSystem" type="system">
|
||||||
<hardware>
|
<hardware>
|
||||||
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
|
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
|
||||||
</hardware>
|
</hardware>
|
||||||
|
|
||||||
<joint name="FR_hip_joint">
|
<joint name="FR_hip_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FR_thigh_joint">
|
<joint name="FR_thigh_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FR_calf_joint">
|
<joint name="FR_calf_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FL_hip_joint">
|
<joint name="FL_hip_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FL_thigh_joint">
|
<joint name="FL_thigh_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FL_calf_joint">
|
<joint name="FL_calf_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RR_hip_joint">
|
<joint name="RR_hip_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RR_thigh_joint">
|
<joint name="RR_thigh_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RR_calf_joint">
|
<joint name="RR_calf_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RL_hip_joint">
|
<joint name="RL_hip_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RL_thigh_joint">
|
<joint name="RL_thigh_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RL_calf_joint">
|
<joint name="RL_calf_joint">
|
||||||
<command_interface name="effort" initial_value="0.0"/>
|
<command_interface name="effort" initial_value="0.0"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<sensor name="imu_sensor">
|
<sensor name="imu_sensor">
|
||||||
<state_interface name="orientation.x"/>
|
<state_interface name="orientation.x"/>
|
||||||
<state_interface name="orientation.y"/>
|
<state_interface name="orientation.y"/>
|
||||||
<state_interface name="orientation.z"/>
|
<state_interface name="orientation.z"/>
|
||||||
<state_interface name="orientation.w"/>
|
<state_interface name="orientation.w"/>
|
||||||
<state_interface name="angular_velocity.x"/>
|
<state_interface name="angular_velocity.x"/>
|
||||||
<state_interface name="angular_velocity.y"/>
|
<state_interface name="angular_velocity.y"/>
|
||||||
<state_interface name="angular_velocity.z"/>
|
<state_interface name="angular_velocity.z"/>
|
||||||
<state_interface name="linear_acceleration.x"/>
|
<state_interface name="linear_acceleration.x"/>
|
||||||
<state_interface name="linear_acceleration.y"/>
|
<state_interface name="linear_acceleration.y"/>
|
||||||
<state_interface name="linear_acceleration.z"/>
|
<state_interface name="linear_acceleration.z"/>
|
||||||
</sensor>
|
</sensor>
|
||||||
</ros2_control>
|
</ros2_control>
|
||||||
|
|
||||||
<gazebo>
|
<gazebo>
|
||||||
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
|
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
|
||||||
<parameters>$(find go2_description)/config/gazebo.yaml</parameters>
|
<parameters>$(find go2_description)/config/gazebo.yaml</parameters>
|
||||||
</plugin>
|
</plugin>
|
||||||
</gazebo>
|
</gazebo>
|
||||||
|
|
||||||
<gazebo reference="trunk">
|
<gazebo reference="trunk">
|
||||||
<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>
|
||||||
</gazebo>
|
</gazebo>
|
||||||
|
|
||||||
<gazebo reference="imu_link">
|
<gazebo reference="imu_link">
|
||||||
<gravity>true</gravity>
|
<gravity>true</gravity>
|
||||||
<sensor name="imu_sensor" type="imu">
|
<sensor name="imu_sensor" type="imu">
|
||||||
<always_on>true</always_on>
|
<always_on>true</always_on>
|
||||||
<update_rate>1000</update_rate>
|
<update_rate>1000</update_rate>
|
||||||
<visualize>true</visualize>
|
<visualize>true</visualize>
|
||||||
<topic>__default_topic__</topic>
|
<topic>__default_topic__</topic>
|
||||||
<plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
|
<plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
|
||||||
<topicName>trunk_imu</topicName>
|
<topicName>trunk_imu</topicName>
|
||||||
<bodyName>imu_link</bodyName>
|
<bodyName>imu_link</bodyName>
|
||||||
<updateRateHZ>1000.0</updateRateHZ>
|
<updateRateHZ>1000.0</updateRateHZ>
|
||||||
<gaussianNoise>0.0</gaussianNoise>
|
<gaussianNoise>0.0</gaussianNoise>
|
||||||
<xyzOffset>0 0 0</xyzOffset>
|
<xyzOffset>0 0 0</xyzOffset>
|
||||||
<rpyOffset>0 0 0</rpyOffset>
|
<rpyOffset>0 0 0</rpyOffset>
|
||||||
<frameName>imu_link</frameName>
|
<frameName>imu_link</frameName>
|
||||||
</plugin>
|
</plugin>
|
||||||
<pose>0 0 0 0 0 0</pose>
|
<pose>0 0 0 0 0 0</pose>
|
||||||
</sensor>
|
</sensor>
|
||||||
</gazebo>
|
</gazebo>
|
||||||
|
|
||||||
</robot>
|
</robot>
|
||||||
|
|
|
@ -25,11 +25,11 @@
|
||||||
<dynamics damping="${damping}" friction="${friction}"/>
|
<dynamics damping="${damping}" friction="${friction}"/>
|
||||||
<xacro:if value="${(mirror_dae == True)}">
|
<xacro:if value="${(mirror_dae == True)}">
|
||||||
<limit effort="${hip_torque_max}" velocity="${hip_velocity_max}" lower="${hip_position_min}"
|
<limit effort="${hip_torque_max}" velocity="${hip_velocity_max}" lower="${hip_position_min}"
|
||||||
upper="${hip_position_max}"/>
|
upper="${hip_position_max}"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<xacro:if value="${(mirror_dae == False)}">
|
<xacro:if value="${(mirror_dae == False)}">
|
||||||
<limit effort="${hip_torque_max}" velocity="${hip_velocity_max}" lower="${-hip_position_max}"
|
<limit effort="${hip_torque_max}" velocity="${hip_velocity_max}" lower="${-hip_position_max}"
|
||||||
upper="${-hip_position_min}"/>
|
upper="${-hip_position_min}"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
|
@ -62,9 +62,9 @@
|
||||||
<origin rpy="0 0 0" xyz="${hip_com_x*front_hind} ${hip_com_y*mirror} ${hip_com_z}"/>
|
<origin rpy="0 0 0" xyz="${hip_com_x*front_hind} ${hip_com_y*mirror} ${hip_com_z}"/>
|
||||||
<mass value="${hip_mass}"/>
|
<mass value="${hip_mass}"/>
|
||||||
<inertia
|
<inertia
|
||||||
ixx="${hip_ixx}" ixy="${hip_ixy*mirror*front_hind}" ixz="${hip_ixz*front_hind}"
|
ixx="${hip_ixx}" ixy="${hip_ixy*mirror*front_hind}" ixz="${hip_ixz*front_hind}"
|
||||||
iyy="${hip_iyy}" iyz="${hip_iyz*mirror}"
|
iyy="${hip_iyy}" iyz="${hip_iyz*mirror}"
|
||||||
izz="${hip_izz}"/>
|
izz="${hip_izz}"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
|
@ -75,7 +75,7 @@
|
||||||
<axis xyz="0 1 0"/>
|
<axis xyz="0 1 0"/>
|
||||||
<dynamics damping="${damping}" friction="${friction}"/>
|
<dynamics damping="${damping}" friction="${friction}"/>
|
||||||
<limit effort="${thigh_torque_max}" velocity="${thigh_velocity_max}" lower="${thigh_position_min}"
|
<limit effort="${thigh_torque_max}" velocity="${thigh_velocity_max}" lower="${thigh_position_min}"
|
||||||
upper="${thigh_position_max}"/>
|
upper="${thigh_position_max}"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
|
|
||||||
|
@ -101,9 +101,9 @@
|
||||||
<origin rpy="0 0 0" xyz="${thigh_com_x} ${thigh_com_y*mirror} ${thigh_com_z}"/>
|
<origin rpy="0 0 0" xyz="${thigh_com_x} ${thigh_com_y*mirror} ${thigh_com_z}"/>
|
||||||
<mass value="${thigh_mass}"/>
|
<mass value="${thigh_mass}"/>
|
||||||
<inertia
|
<inertia
|
||||||
ixx="${thigh_ixx}" ixy="${thigh_ixy*mirror}" ixz="${thigh_ixz}"
|
ixx="${thigh_ixx}" ixy="${thigh_ixy*mirror}" ixz="${thigh_ixz}"
|
||||||
iyy="${thigh_iyy}" iyz="${thigh_iyz*mirror}"
|
iyy="${thigh_iyy}" iyz="${thigh_iyz*mirror}"
|
||||||
izz="${thigh_izz}"/>
|
izz="${thigh_izz}"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
|
@ -115,7 +115,7 @@
|
||||||
<axis xyz="0 1 0"/>
|
<axis xyz="0 1 0"/>
|
||||||
<dynamics damping="${damping}" friction="${friction}"/>
|
<dynamics damping="${damping}" friction="${friction}"/>
|
||||||
<limit effort="${calf_torque_max}" velocity="${calf_velocity_max}" lower="${calf_position_min}"
|
<limit effort="${calf_torque_max}" velocity="${calf_velocity_max}" lower="${calf_position_min}"
|
||||||
upper="${calf_position_max}"/>
|
upper="${calf_position_max}"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
|
|
||||||
|
@ -136,9 +136,9 @@
|
||||||
<origin rpy="0 0 0" xyz="${calf_com_x} ${calf_com_y} ${calf_com_z}"/>
|
<origin rpy="0 0 0" xyz="${calf_com_x} ${calf_com_y} ${calf_com_z}"/>
|
||||||
<mass value="${calf_mass}"/>
|
<mass value="${calf_mass}"/>
|
||||||
<inertia
|
<inertia
|
||||||
ixx="${calf_ixx}" ixy="${calf_ixy}" ixz="${calf_ixz}"
|
ixx="${calf_ixx}" ixy="${calf_ixy}" ixz="${calf_ixz}"
|
||||||
iyy="${calf_iyy}" iyz="${calf_iyz}"
|
iyy="${calf_iyy}" iyz="${calf_iyz}"
|
||||||
izz="${calf_izz}"/>
|
izz="${calf_izz}"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
|
@ -165,9 +165,9 @@
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="${foot_mass}"/>
|
<mass value="${foot_mass}"/>
|
||||||
<inertia
|
<inertia
|
||||||
ixx="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}" ixy="0.0" ixz="0.0"
|
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"
|
iyy="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}" iyz="0.0"
|
||||||
izz="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}"/>
|
izz="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
|
|
|
@ -1,40 +1,40 @@
|
||||||
<?xml version="1.0"?>
|
<?xml version="1.0"?>
|
||||||
<robot>
|
<robot>
|
||||||
|
|
||||||
<material name="black">
|
<material name="black">
|
||||||
<color rgba="0.0 0.0 0.0 1.0"/>
|
<color rgba="0.0 0.0 0.0 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<material name="blue">
|
<material name="blue">
|
||||||
<color rgba="0.0 0.0 0.8 1.0"/>
|
<color rgba="0.0 0.0 0.8 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<material name="green">
|
<material name="green">
|
||||||
<color rgba="0.0 0.8 0.0 1.0"/>
|
<color rgba="0.0 0.8 0.0 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<material name="grey">
|
<material name="grey">
|
||||||
<color rgba="0.2 0.2 0.2 0.0"/>
|
<color rgba="0.2 0.2 0.2 0.0"/>
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<material name="silver">
|
<material name="silver">
|
||||||
<color rgba="${233/255} ${233/255} ${216/255} 1.0"/>
|
<color rgba="${233/255} ${233/255} ${216/255} 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<material name="orange">
|
<material name="orange">
|
||||||
<color rgba="${255/255} ${108/255} ${10/255} 1.0"/>
|
<color rgba="${255/255} ${108/255} ${10/255} 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<material name="brown">
|
<material name="brown">
|
||||||
<color rgba="${222/255} ${207/255} ${195/255} 1.0"/>
|
<color rgba="${222/255} ${207/255} ${195/255} 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<material name="red">
|
<material name="red">
|
||||||
<color rgba="0.8 0.0 0.0 1.0"/>
|
<color rgba="0.8 0.0 0.0 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<material name="white">
|
<material name="white">
|
||||||
<color rgba="1.0 1.0 1.0 1.0"/>
|
<color rgba="1.0 1.0 1.0 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
</robot>
|
</robot>
|
||||||
|
|
|
@ -2,136 +2,154 @@
|
||||||
|
|
||||||
<robot name="go2" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
<robot name="go2" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
<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:arg name="CLASSIC" default="false"/>
|
||||||
|
|
||||||
<xacro:include filename="$(find go2_description)/xacro/const.xacro"/>
|
<xacro:include filename="$(find go2_description)/xacro/const.xacro"/>
|
||||||
<xacro:include filename="$(find go2_description)/xacro/materials.xacro"/>
|
<xacro:include filename="$(find go2_description)/xacro/materials.xacro"/>
|
||||||
<xacro:include filename="$(find go2_description)/xacro/leg.xacro"/>
|
<xacro:include filename="$(find go2_description)/xacro/leg.xacro"/>
|
||||||
|
|
||||||
<xacro:if value="$(arg GAZEBO)">
|
<xacro:if value="$(arg GAZEBO)">
|
||||||
<xacro:if value="$(arg CLASSIC)">
|
<xacro:if value="$(arg CLASSIC)">
|
||||||
<xacro:include filename="$(find go2_description)/xacro/gazebo_classic.xacro"/>
|
<xacro:include filename="$(find go2_description)/xacro/gazebo_classic.xacro"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<xacro:unless value="$(arg CLASSIC)">
|
<xacro:unless value="$(arg CLASSIC)">
|
||||||
<xacro:include filename="$(find go2_description)/xacro/gazebo.xacro"/>
|
<xacro:include filename="$(find go2_description)/xacro/gazebo.xacro"/>
|
||||||
</xacro:unless>
|
</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 go2_description)/xacro/ros2_control.xacro"/>
|
||||||
</xacro:unless>
|
</xacro:unless>
|
||||||
|
|
||||||
|
|
||||||
<!-- <xacro:stairs stairs="15" xpos="0" ypos="0" zpos="0" /> -->
|
<!-- <xacro:stairs stairs="15" xpos="0" ypos="0" zpos="0" /> -->
|
||||||
|
|
||||||
<!-- Rotor related joint and link is only for demonstrate location. -->
|
<!-- Rotor related joint and link is only for demonstrate location. -->
|
||||||
<!-- Actually, the rotor will rotate and the joint is not fixed. Reduction ratio should be considered. -->
|
<!-- Actually, the rotor will rotate and the joint is not fixed. Reduction ratio should be considered. -->
|
||||||
|
|
||||||
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
|
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
|
||||||
<xacro:if value="$(arg DEBUG)">
|
<xacro:if value="$(arg DEBUG)">
|
||||||
<link name="world"/>
|
<link name="world"/>
|
||||||
<joint name="base_static_joint" type="fixed">
|
<joint name="base_static_joint" type="fixed">
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<parent link="world"/>
|
<parent link="world"/>
|
||||||
<child link="base"/>
|
<child link="base"/>
|
||||||
</joint>
|
</joint>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
|
|
||||||
<link name="base">
|
<link name="base">
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.001 0.001 0.001"/>
|
<box size="0.001 0.001 0.001"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</visual>
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="floating_base" type="fixed">
|
<joint name="floating_base" type="fixed">
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<parent link="base"/>
|
<parent link="base"/>
|
||||||
<child link="trunk"/>
|
<child link="trunk"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="trunk">
|
<link name="trunk">
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="file://$(find go2_description)/meshes/trunk.dae" scale="1 1 1"/>
|
<mesh filename="file://$(find go2_description)/meshes/trunk.dae" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<!-- <material name="orange"/> -->
|
<!-- <material name="orange"/> -->
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="${trunk_length} ${trunk_width} ${trunk_height}"/>
|
<box size="${trunk_length} ${trunk_width} ${trunk_height}"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<inertial>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="${trunk_com_x} ${trunk_com_y} ${trunk_com_z}"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<mass value="${trunk_mass}"/>
|
<geometry>
|
||||||
<inertia
|
<box size="0.1881 0.04675 0.057"/>
|
||||||
ixx="${trunk_ixx}" ixy="${trunk_ixy}" ixz="${trunk_ixz}"
|
</geometry>
|
||||||
iyy="${trunk_iyy}" iyz="${trunk_iyz}"
|
</collision>
|
||||||
izz="${trunk_izz}"/>
|
<collision>
|
||||||
</inertial>
|
<origin rpy="0 0 0" xyz="0.285 0 0.01"/>
|
||||||
</link>
|
<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>
|
||||||
|
<origin rpy="0 0 0" xyz="${trunk_com_x} ${trunk_com_y} ${trunk_com_z}"/>
|
||||||
|
<mass value="${trunk_mass}"/>
|
||||||
|
<inertia
|
||||||
|
ixx="${trunk_ixx}" ixy="${trunk_ixy}" ixz="${trunk_ixz}"
|
||||||
|
iyy="${trunk_iyy}" iyz="${trunk_iyz}"
|
||||||
|
izz="${trunk_izz}"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
<joint name="imu_joint" type="fixed">
|
<joint name="imu_joint" type="fixed">
|
||||||
<parent link="trunk"/>
|
<parent link="trunk"/>
|
||||||
<child link="imu_link"/>
|
<child link="imu_link"/>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="imu_link">
|
<link name="imu_link">
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="0.001"/>
|
<mass value="0.001"/>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<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"/>
|
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.001 0.001 0.001"/>
|
<box size="0.001 0.001 0.001"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<!-- <material name="red"/> -->
|
<!-- <material name="red"/> -->
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size=".001 .001 .001"/>
|
<box size=".001 .001 .001"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
<!--
|
<!--
|
||||||
<joint name="load_joint" type="fixed">
|
<joint name="load_joint" type="fixed">
|
||||||
<parent link="trunk"/>
|
<parent link="trunk"/>
|
||||||
<child link="load_link"/>
|
<child link="load_link"/>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="load_link">
|
<link name="load_link">
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="5"/>
|
<mass value="5"/>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
|
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0.2"/>
|
<origin rpy="0 0 0" xyz="0 0 0.2"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.5 0.3 0.2"/>
|
<box size="0.5 0.3 0.2"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size=".001 .001 .001"/>
|
<box size=".001 .001 .001"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
-->
|
-->
|
||||||
<xacro:leg name="FR" mirror="-1" mirror_dae= "False" front_hind="1" front_hind_dae="True" />
|
<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="FL" mirror="1" mirror_dae="True" front_hind="1" front_hind_dae="True"/>
|
||||||
<xacro:leg name="RR" mirror="-1" mirror_dae="False" front_hind="-1" front_hind_dae="False" />
|
<xacro:leg name="RR" mirror="-1" mirror_dae="False" front_hind="-1" front_hind_dae="False"/>
|
||||||
<xacro:leg name="RL" mirror="1" mirror_dae="True" front_hind="-1" front_hind_dae="False" />
|
<xacro:leg name="RL" mirror="1" mirror_dae="True" front_hind="-1" front_hind_dae="False"/>
|
||||||
</robot>
|
</robot>
|
||||||
|
|
|
@ -1,176 +1,176 @@
|
||||||
<?xml version="1.0"?>
|
<?xml version="1.0"?>
|
||||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
<ros2_control name="UnitreeSystem" type="system">
|
<ros2_control name="UnitreeSystem" type="system">
|
||||||
|
|
||||||
<hardware>
|
<hardware>
|
||||||
<plugin>hardware_unitree_mujoco/HardwareUnitree</plugin>
|
<plugin>hardware_unitree_mujoco/HardwareUnitree</plugin>
|
||||||
</hardware>
|
</hardware>
|
||||||
|
|
||||||
<joint name="FR_hip_joint">
|
<joint name="FR_hip_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FR_thigh_joint">
|
<joint name="FR_thigh_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FR_calf_joint">
|
<joint name="FR_calf_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FL_hip_joint">
|
<joint name="FL_hip_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FL_thigh_joint">
|
<joint name="FL_thigh_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="FL_calf_joint">
|
<joint name="FL_calf_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RR_hip_joint">
|
<joint name="RR_hip_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RR_thigh_joint">
|
<joint name="RR_thigh_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RR_calf_joint">
|
<joint name="RR_calf_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RL_hip_joint">
|
<joint name="RL_hip_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RL_thigh_joint">
|
<joint name="RL_thigh_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="RL_calf_joint">
|
<joint name="RL_calf_joint">
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<command_interface name="velocity"/>
|
<command_interface name="velocity"/>
|
||||||
<command_interface name="effort"/>
|
<command_interface name="effort"/>
|
||||||
<command_interface name="kp"/>
|
<command_interface name="kp"/>
|
||||||
<command_interface name="kd"/>
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
<state_interface name="effort"/>
|
<state_interface name="effort"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<sensor name="imu_sensor">
|
<sensor name="imu_sensor">
|
||||||
<state_interface name="orientation.w"/>
|
<state_interface name="orientation.w"/>
|
||||||
<state_interface name="orientation.x"/>
|
<state_interface name="orientation.x"/>
|
||||||
<state_interface name="orientation.y"/>
|
<state_interface name="orientation.y"/>
|
||||||
<state_interface name="orientation.z"/>
|
<state_interface name="orientation.z"/>
|
||||||
<state_interface name="angular_velocity.x"/>
|
<state_interface name="angular_velocity.x"/>
|
||||||
<state_interface name="angular_velocity.y"/>
|
<state_interface name="angular_velocity.y"/>
|
||||||
<state_interface name="angular_velocity.z"/>
|
<state_interface name="angular_velocity.z"/>
|
||||||
<state_interface name="linear_acceleration.x"/>
|
<state_interface name="linear_acceleration.x"/>
|
||||||
<state_interface name="linear_acceleration.y"/>
|
<state_interface name="linear_acceleration.y"/>
|
||||||
<state_interface name="linear_acceleration.z"/>
|
<state_interface name="linear_acceleration.z"/>
|
||||||
</sensor>
|
</sensor>
|
||||||
|
|
||||||
<sensor name="foot_force">
|
<sensor name="foot_force">
|
||||||
<state_interface name="FR"/>
|
<state_interface name="FR"/>
|
||||||
<state_interface name="FL"/>
|
<state_interface name="FL"/>
|
||||||
<state_interface name="RR"/>
|
<state_interface name="RR"/>
|
||||||
<state_interface name="RL"/>
|
<state_interface name="RL"/>
|
||||||
</sensor>
|
</sensor>
|
||||||
|
|
||||||
</ros2_control>
|
</ros2_control>
|
||||||
|
|
||||||
</robot>
|
</robot>
|
||||||
|
|
|
@ -2,41 +2,41 @@
|
||||||
|
|
||||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
<xacro:macro name="leg_transmission" params="name">
|
<xacro:macro name="leg_transmission" params="name">
|
||||||
|
|
||||||
<transmission name="${name}_hip_tran">
|
<transmission name="${name}_hip_tran">
|
||||||
<type>transmission_interface/SimpleTransmission</type>
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
<joint name="${name}_hip_joint">
|
<joint name="${name}_hip_joint">
|
||||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||||
</joint>
|
</joint>
|
||||||
<actuator name="${name}_hip_motor">
|
<actuator name="${name}_hip_motor">
|
||||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||||
<mechanicalReduction>1</mechanicalReduction>
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
</actuator>
|
</actuator>
|
||||||
</transmission>
|
</transmission>
|
||||||
|
|
||||||
<transmission name="${name}_thigh_tran">
|
<transmission name="${name}_thigh_tran">
|
||||||
<type>transmission_interface/SimpleTransmission</type>
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
<joint name="${name}_thigh_joint">
|
<joint name="${name}_thigh_joint">
|
||||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||||
</joint>
|
</joint>
|
||||||
<actuator name="${name}_thigh_motor">
|
<actuator name="${name}_thigh_motor">
|
||||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||||
<mechanicalReduction>1</mechanicalReduction>
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
</actuator>
|
</actuator>
|
||||||
</transmission>
|
</transmission>
|
||||||
|
|
||||||
<transmission name="${name}_calf_tran">
|
<transmission name="${name}_calf_tran">
|
||||||
<type>transmission_interface/SimpleTransmission</type>
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
<joint name="${name}_calf_joint">
|
<joint name="${name}_calf_joint">
|
||||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||||
</joint>
|
</joint>
|
||||||
<actuator name="${name}_calf_motor">
|
<actuator name="${name}_calf_motor">
|
||||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||||
<mechanicalReduction>1</mechanicalReduction>
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
</actuator>
|
</actuator>
|
||||||
</transmission>
|
</transmission>
|
||||||
|
|
||||||
</xacro:macro>
|
</xacro:macro>
|
||||||
|
|
||||||
</robot>
|
</robot>
|
||||||
|
|
|
@ -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
|
||||||
|
|
|
@ -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
|
||||||
|
|
|
@ -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"/>
|
||||||
|
|
|
@ -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>
|
|
@ -1,220 +1,226 @@
|
||||||
<?xml version="1.0"?>
|
<?xml version="1.0"?>
|
||||||
<robot name="cyber_dog" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
<robot name="cyber_dog" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
<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:include filename="gazebo.xacro"/>
|
<xacro:if value="$(arg CLASSIC)">
|
||||||
</xacro:if>
|
<xacro:include filename="gazebo_classic.xacro"/>
|
||||||
<xacro:unless value="$(arg GAZEBO)">
|
</xacro:if>
|
||||||
<xacro:include filename="ros2_control.xacro"/>
|
<xacro:unless value="$(arg CLASSIC)">
|
||||||
</xacro:unless>
|
<xacro:include filename="gazebo.xacro"/>
|
||||||
|
</xacro:unless>
|
||||||
|
</xacro:if>
|
||||||
|
<xacro:unless value="$(arg GAZEBO)">
|
||||||
|
<xacro:include filename="ros2_control.xacro"/>
|
||||||
|
</xacro:unless>
|
||||||
|
|
||||||
|
|
||||||
<link name="base">
|
<link name="base">
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.001 0.001 0.001"/>
|
<box size="0.001 0.001 0.001"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</visual>
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="floating_base" type="fixed">
|
<joint name="floating_base" type="fixed">
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<parent link="base"/>
|
<parent link="base"/>
|
||||||
<child link="body"/>
|
<child link="body"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="body">
|
<link name="body">
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="file://$(find cyberdog_description)/meshes/body.dae" scale="1 1 1"/>
|
<mesh filename="file://$(find cyberdog_description)/meshes/body.dae" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="${body_length} ${body_width} ${body_height}"/>
|
<box size="${body_length} ${body_width} ${body_height}"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin rpy="0 0 0" xyz="${body_com_x} ${body_com_y} ${body_com_z}"/>
|
<origin rpy="0 0 0" xyz="${body_com_x} ${body_com_y} ${body_com_z}"/>
|
||||||
<mass value="${body_mass}"/>
|
<mass value="${body_mass}"/>
|
||||||
<inertia ixx="${body_ixx}" ixy="${body_ixy}" ixz="${body_ixz}" iyy="${body_iyy}" iyz="${body_iyz}"
|
<inertia ixx="${body_ixx}" ixy="${body_ixy}" ixz="${body_ixz}" iyy="${body_iyy}" iyz="${body_iyz}"
|
||||||
izz="${body_izz}"/>
|
izz="${body_izz}"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="imu_joint" type="fixed">
|
<joint name="imu_joint" type="fixed">
|
||||||
<parent link="body"/>
|
<parent link="body"/>
|
||||||
<child link="imu_link"/>
|
<child link="imu_link"/>
|
||||||
<origin rpy="0 0 0" xyz="33.4e-3 -17.2765e-3 51.0469e-3"/>
|
<origin rpy="0 0 0" xyz="33.4e-3 -17.2765e-3 51.0469e-3"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="imu_link">
|
<link name="imu_link">
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="0.001"/>
|
<mass value="0.001"/>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<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"/>
|
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.001 0.001 0.001"/>
|
<box size="0.001 0.001 0.001"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size=".001 .001 .001"/>
|
<box size=".001 .001 .001"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="scan_joint" type="fixed">
|
<joint name="scan_joint" type="fixed">
|
||||||
<parent link="body"/>
|
<parent link="body"/>
|
||||||
<child link="lidar_link"/>
|
<child link="lidar_link"/>
|
||||||
<origin rpy="0 0 0" xyz="0.21425 0 0.0908"/>
|
<origin rpy="0 0 0" xyz="0.21425 0 0.0908"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="lidar_link">
|
<link name="lidar_link">
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="0.001"/>
|
<mass value="0.001"/>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<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"/>
|
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="D435_camera_joint" type="fixed">
|
<joint name="D435_camera_joint" type="fixed">
|
||||||
<parent link="body"/>
|
<parent link="body"/>
|
||||||
<child link="D435_camera_link"/>
|
<child link="D435_camera_link"/>
|
||||||
<origin rpy="0 0 0" xyz="271.994e-3 25e-3 114.912e-3"/>
|
<origin rpy="0 0 0" xyz="271.994e-3 25e-3 114.912e-3"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="D435_camera_link">
|
<link name="D435_camera_link">
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="0.001"/>
|
<mass value="0.001"/>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<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"/>
|
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.001 0.001 0.001"/>
|
<box size="0.001 0.001 0.001"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size=".001 .001 .001"/>
|
<box size=".001 .001 .001"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="RGB_camera_joint" type="fixed">
|
<joint name="RGB_camera_joint" type="fixed">
|
||||||
<parent link="body"/>
|
<parent link="body"/>
|
||||||
<child link="RGB_camera_link"/>
|
<child link="RGB_camera_link"/>
|
||||||
<origin rpy="0 0 0" xyz="275.76e-3 0 125.794e-3"/>
|
<origin rpy="0 0 0" xyz="275.76e-3 0 125.794e-3"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="RGB_camera_link">
|
<link name="RGB_camera_link">
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="0.001"/>
|
<mass value="0.001"/>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<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"/>
|
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.001 0.001 0.001"/>
|
<box size="0.001 0.001 0.001"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size=".001 .001 .001"/>
|
<box size=".001 .001 .001"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="AI_camera_joint" type="fixed">
|
<joint name="AI_camera_joint" type="fixed">
|
||||||
<parent link="body"/>
|
<parent link="body"/>
|
||||||
<child link="AI_camera_link"/>
|
<child link="AI_camera_link"/>
|
||||||
<origin rpy="0 0 0" xyz="290.228e-3 0 147.420e-3"/>
|
<origin rpy="0 0 0" xyz="290.228e-3 0 147.420e-3"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="AI_camera_link">
|
<link name="AI_camera_link">
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="0.001"/>
|
<mass value="0.001"/>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<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"/>
|
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.001 0.001 0.001"/>
|
<box size="0.001 0.001 0.001"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size=".001 .001 .001"/>
|
<box size=".001 .001 .001"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<xacro:leg name="FR" mirror="-1" mirror_dae="False" front_hind="1" front_hind_dae="True">
|
<xacro:leg name="FR" mirror="-1" mirror_dae="False" front_hind="1" front_hind_dae="True">
|
||||||
<origin rpy="0 0 0" xyz="${abad_offset_x} ${-abad_offset_y} 0"/>
|
<origin rpy="0 0 0" xyz="${abad_offset_x} ${-abad_offset_y} 0"/>
|
||||||
</xacro:leg>
|
</xacro:leg>
|
||||||
|
|
||||||
<xacro:leg name="FL" mirror="1" mirror_dae="True" front_hind="1" front_hind_dae="True">
|
<xacro:leg name="FL" mirror="1" mirror_dae="True" front_hind="1" front_hind_dae="True">
|
||||||
<origin rpy="0 0 0" xyz="${abad_offset_x} ${abad_offset_y} 0"/>
|
<origin rpy="0 0 0" xyz="${abad_offset_x} ${abad_offset_y} 0"/>
|
||||||
</xacro:leg>
|
</xacro:leg>
|
||||||
|
|
||||||
<xacro:leg name="RR" mirror="-1" mirror_dae="False" front_hind="-1" front_hind_dae="False">
|
<xacro:leg name="RR" mirror="-1" mirror_dae="False" front_hind="-1" front_hind_dae="False">
|
||||||
<origin rpy="0 0 0" xyz="${-abad_offset_x} ${-abad_offset_y} 0"/>
|
<origin rpy="0 0 0" xyz="${-abad_offset_x} ${-abad_offset_y} 0"/>
|
||||||
</xacro:leg>
|
</xacro:leg>
|
||||||
|
|
||||||
<xacro:leg name="RL" mirror="1" mirror_dae="True" front_hind="-1" front_hind_dae="False">
|
<xacro:leg name="RL" mirror="1" mirror_dae="True" front_hind="-1" front_hind_dae="False">
|
||||||
<origin rpy="0 0 0" xyz="${-abad_offset_x} ${abad_offset_y} 0"/>
|
<origin rpy="0 0 0" xyz="${-abad_offset_x} ${abad_offset_y} 0"/>
|
||||||
</xacro:leg>
|
</xacro:leg>
|
||||||
|
|
||||||
<!-- This link is only for head collision -->
|
<!-- This link is only for head collision -->
|
||||||
<joint name="head_joint" type="fixed">
|
<joint name="head_joint" type="fixed">
|
||||||
<parent link="body"/>
|
<parent link="body"/>
|
||||||
<child link="head"/>
|
<child link="head"/>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
</joint>
|
</joint>
|
||||||
<link name="head">
|
<link name="head">
|
||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0.256 0 0.120"/>
|
<origin rpy="0 0 0" xyz="0.256 0 0.120"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.076 0.060 0.040"/>
|
<box size="0.076 0.060 0.040"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0.225 0 0.150"/>
|
<origin rpy="0 0 0" xyz="0.225 0 0.150"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.020 0.080 0.100"/>
|
<box size="0.020 0.080 0.100"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<gazebo reference="body">
|
<gazebo reference="body">
|
||||||
<visual>
|
<visual>
|
||||||
<material>
|
<material>
|
||||||
<ambient>.1 .1 .1 1.0</ambient>
|
<ambient>.1 .1 .1 1.0</ambient>
|
||||||
<diffuse>.1 .1 .1 1.0</diffuse>
|
<diffuse>.1 .1 .1 1.0</diffuse>
|
||||||
<specular>.1 .1 .1 1.0</specular>
|
<specular>.1 .1 .1 1.0</specular>
|
||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
</gazebo>
|
</gazebo>
|
||||||
|
|
||||||
</robot>
|
</robot>
|
Loading…
Reference in New Issue