diff --git a/src/sherpa/config/ackermann_controller.yaml b/src/sherpa/config/ackermann_controller.yaml index 85a353a..7a61da6 100644 --- a/src/sherpa/config/ackermann_controller.yaml +++ b/src/sherpa/config/ackermann_controller.yaml @@ -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] diff --git a/src/sherpa/launch/simulator.launch.py b/src/sherpa/launch/simulator.launch.py index d0f9168..4e85f23 100644 --- a/src/sherpa/launch/simulator.launch.py +++ b/src/sherpa/launch/simulator.launch.py @@ -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' ) diff --git a/src/sherpa/urdf/sherpa.xacro b/src/sherpa/urdf/sherpa.xacro index 3f43762..c0f4349 100644 --- a/src/sherpa/urdf/sherpa.xacro +++ b/src/sherpa/urdf/sherpa.xacro @@ -24,8 +24,8 @@ - - + + diff --git a/src/sherpa/worlds/raceway.world b/src/sherpa/worlds/raceway.world index 35d4239..781ce53 100644 --- a/src/sherpa/worlds/raceway.world +++ b/src/sherpa/worlds/raceway.world @@ -13,6 +13,9 @@ name="ignition::gazebo::systems::Sensors"> ogre2 + +