Merge branch 'master' of git.anxietyprime.de:SHERPA/sherpa_ros2_ws

This commit is contained in:
2025-08-16 11:09:37 +02:00
3 changed files with 3 additions and 3 deletions

View File

@@ -26,7 +26,7 @@ ackermann_controller:
rear_wheels_radius: 0.15 # Radius of wheels [m]
# Limits
max_steering_angle: 0.785 # [rad] ~45 degrees
max_steering_angle: 1.0 # [rad] ~45 degrees
max_speed: 10.0 # [m/s]
min_speed: -5.0 # [m/s]

View File

@@ -78,7 +78,7 @@ def generate_launch_description():
'ros2', 'run', 'ros_gz_sim', 'create',
'-name', 'sherpa',
'-topic', 'robot_description',
'-x', '0', '-y', '0', '-z', '2'
'-x', '1.5', '-y', '9.5', '-z', '0.2'
],
output='screen'
)

View File

@@ -25,7 +25,7 @@
<xacro:include filename="components/wheel.xacro"/>
<xacro:include filename="components/ouster_lidar.xacro"/>
<xacro:camera name="front_camera" parent="base" xyz="0 0 0.75" rpy="0 0 0" frequency="30" fov="90" topic="/front_camera"/>
<xacro:camera name="front_camera" parent="base" xyz="0 0 0.75" rpy="0 0 0" frequency="30" fov="120" topic="/front_camera"/>
<xacro:imu name="imu" parent="base" xyz="0 0 0.35" rpy="0 0.05 0" frequency="300" topic="/imu"/>
<xacro:ouster_lidar name="lidar" parent="base" xyz="0 0 0.35" rpy="0 0.05 0" model="vlp16" frequency="10" topic="/velodyne_points"/>