fixed sim

This commit is contained in:
2025-05-02 10:13:00 +02:00
parent 85ab9f3fd9
commit a12834557d
4 changed files with 9 additions and 6 deletions

View File

@@ -15,8 +15,8 @@ ackermann_controller:
position_feedback: false
# Interfaces
rear_wheels_names: ["wheel_bl_joint", "wheel_br_joint"]
front_wheels_names: ["steer_fl_joint", "steer_fr_joint"]
rear_wheels_names: ["wheel_br_joint", "wheel_bl_joint"]
front_wheels_names: ["steer_fr_joint", "steer_fl_joint"]
# Physical parameters
wheelbase: 0.6 # Distance between front and rear axles [m]

View File

@@ -69,7 +69,7 @@ def generate_launch_description():
'0', '0', '0',
'0', '0', '0',
'velodyne',
'base_link',
'lidar_link',
]
)
@@ -78,7 +78,7 @@ def generate_launch_description():
'ros2', 'run', 'ros_gz_sim', 'create',
'-name', 'sherpa',
'-topic', 'robot_description',
'-x', '0', '-y', '0', '-z', '0.5'
'-x', '0', '-y', '0', '-z', '26'
],
#output='screen'
)

View File

@@ -24,8 +24,8 @@
<xacro:include filename="components/wheel.xacro"/>
<xacro:include filename="components/ouster_lidar.xacro"/>
<xacro:imu name="imu" parent="base" xyz="0 0 0.156" rpy="0 0 0" frequency="300"/>
<xacro:ouster_lidar name="lidar" parent="base" xyz="0 0 0.35" rpy="0 0 0" model="OS1" frequency="10" topic="/points"/>
<xacro:imu name="imu" parent="base" xyz="0 0 0.35" rpy="0 0 0" frequency="300"/>
<xacro:ouster_lidar name="lidar" parent="base" xyz="0 0 0.35" rpy="0 0 0" model="vlp16" frequency="10" topic="/points"/>
<link name="steer_fl_link">
<inertial>

View File

@@ -13,6 +13,9 @@
name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
<plugin filename="gz-sim-imu-system"
name="gz::sim::systems::Imu">
</plugin>
<plugin
filename="ignition-gazebo-user-commands-system"
name="ignition::gazebo::systems::UserCommands">