fixed sim
This commit is contained in:
@@ -15,8 +15,8 @@ ackermann_controller:
|
|||||||
position_feedback: false
|
position_feedback: false
|
||||||
|
|
||||||
# Interfaces
|
# Interfaces
|
||||||
rear_wheels_names: ["wheel_bl_joint", "wheel_br_joint"]
|
rear_wheels_names: ["wheel_br_joint", "wheel_bl_joint"]
|
||||||
front_wheels_names: ["steer_fl_joint", "steer_fr_joint"]
|
front_wheels_names: ["steer_fr_joint", "steer_fl_joint"]
|
||||||
|
|
||||||
# Physical parameters
|
# Physical parameters
|
||||||
wheelbase: 0.6 # Distance between front and rear axles [m]
|
wheelbase: 0.6 # Distance between front and rear axles [m]
|
||||||
|
|||||||
@@ -69,7 +69,7 @@ def generate_launch_description():
|
|||||||
'0', '0', '0',
|
'0', '0', '0',
|
||||||
'0', '0', '0',
|
'0', '0', '0',
|
||||||
'velodyne',
|
'velodyne',
|
||||||
'base_link',
|
'lidar_link',
|
||||||
]
|
]
|
||||||
)
|
)
|
||||||
|
|
||||||
@@ -78,7 +78,7 @@ def generate_launch_description():
|
|||||||
'ros2', 'run', 'ros_gz_sim', 'create',
|
'ros2', 'run', 'ros_gz_sim', 'create',
|
||||||
'-name', 'sherpa',
|
'-name', 'sherpa',
|
||||||
'-topic', 'robot_description',
|
'-topic', 'robot_description',
|
||||||
'-x', '0', '-y', '0', '-z', '0.5'
|
'-x', '0', '-y', '0', '-z', '26'
|
||||||
],
|
],
|
||||||
#output='screen'
|
#output='screen'
|
||||||
)
|
)
|
||||||
|
|||||||
@@ -24,8 +24,8 @@
|
|||||||
<xacro:include filename="components/wheel.xacro"/>
|
<xacro:include filename="components/wheel.xacro"/>
|
||||||
<xacro:include filename="components/ouster_lidar.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: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="OS1" frequency="10" topic="/points"/>
|
<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">
|
<link name="steer_fl_link">
|
||||||
<inertial>
|
<inertial>
|
||||||
|
|||||||
@@ -13,6 +13,9 @@
|
|||||||
name="ignition::gazebo::systems::Sensors">
|
name="ignition::gazebo::systems::Sensors">
|
||||||
<render_engine>ogre2</render_engine>
|
<render_engine>ogre2</render_engine>
|
||||||
</plugin>
|
</plugin>
|
||||||
|
<plugin filename="gz-sim-imu-system"
|
||||||
|
name="gz::sim::systems::Imu">
|
||||||
|
</plugin>
|
||||||
<plugin
|
<plugin
|
||||||
filename="ignition-gazebo-user-commands-system"
|
filename="ignition-gazebo-user-commands-system"
|
||||||
name="ignition::gazebo::systems::UserCommands">
|
name="ignition::gazebo::systems::UserCommands">
|
||||||
|
|||||||
Reference in New Issue
Block a user