changed default track to raceway
This commit is contained in:
@@ -32,4 +32,10 @@
|
|||||||
gz_topic_name: "imu"
|
gz_topic_name: "imu"
|
||||||
ros_type_name: "sensor_msgs/msg/Imu"
|
ros_type_name: "sensor_msgs/msg/Imu"
|
||||||
gz_type_name: "gz.msgs.IMU"
|
gz_type_name: "gz.msgs.IMU"
|
||||||
direction: GZ_TO_ROS
|
direction: GZ_TO_ROS
|
||||||
|
|
||||||
|
- ros_topic_name: "/cmd_vel_in"
|
||||||
|
gz_topic_name: "cmd_vel"
|
||||||
|
ros_type_name: "geometry_msgs/msg/Twist"
|
||||||
|
gz_type_name: "gz.msgs.Twist"
|
||||||
|
direction: GZ_TO_ROS
|
||||||
|
|||||||
@@ -18,7 +18,7 @@ def generate_launch_description():
|
|||||||
pkg_share = get_package_share_directory(pkg_name)
|
pkg_share = get_package_share_directory(pkg_name)
|
||||||
pkg_prefix = os.path.dirname(pkg_share)
|
pkg_prefix = os.path.dirname(pkg_share)
|
||||||
|
|
||||||
world_path = os.path.join(pkg_share, 'worlds', 'empty.world')
|
world_path = os.path.join(pkg_share, 'worlds', 'raceway.world')
|
||||||
xacro_file = os.path.join(pkg_share, 'urdf', 'sherpa.xacro')
|
xacro_file = os.path.join(pkg_share, 'urdf', 'sherpa.xacro')
|
||||||
|
|
||||||
# create nodes
|
# create nodes
|
||||||
@@ -33,7 +33,7 @@ def generate_launch_description():
|
|||||||
'ros2', 'launch', 'ros_gz_sim', 'gz_sim.launch.py',
|
'ros2', 'launch', 'ros_gz_sim', 'gz_sim.launch.py',
|
||||||
f'gz_args:=-r {world_path}'
|
f'gz_args:=-r {world_path}'
|
||||||
],
|
],
|
||||||
output='screen'
|
#output='screen'
|
||||||
)
|
)
|
||||||
|
|
||||||
state_publisher = Node(
|
state_publisher = Node(
|
||||||
@@ -50,7 +50,7 @@ def generate_launch_description():
|
|||||||
package='controller_manager',
|
package='controller_manager',
|
||||||
executable='spawner',
|
executable='spawner',
|
||||||
arguments=['ackermann_controller'],
|
arguments=['ackermann_controller'],
|
||||||
output='screen'
|
#output='screen'
|
||||||
)
|
)
|
||||||
|
|
||||||
joint_state_broadcaster = Node(
|
joint_state_broadcaster = Node(
|
||||||
@@ -58,7 +58,7 @@ def generate_launch_description():
|
|||||||
executable='spawner',
|
executable='spawner',
|
||||||
arguments=['joint_state_broadcaster', '--controller-manager', '/controller_manager'],
|
arguments=['joint_state_broadcaster', '--controller-manager', '/controller_manager'],
|
||||||
parameters=[{'use_sim_time': True}],
|
parameters=[{'use_sim_time': True}],
|
||||||
output='screen'
|
#output='screen'
|
||||||
)
|
)
|
||||||
|
|
||||||
static_tf = Node(
|
static_tf = Node(
|
||||||
@@ -80,6 +80,15 @@ def generate_launch_description():
|
|||||||
'-topic', 'robot_description',
|
'-topic', 'robot_description',
|
||||||
'-x', '0', '-y', '0', '-z', '0.5'
|
'-x', '0', '-y', '0', '-z', '0.5'
|
||||||
],
|
],
|
||||||
|
#output='screen'
|
||||||
|
)
|
||||||
|
|
||||||
|
twist_stamper = Node(
|
||||||
|
package="twist_stamper",
|
||||||
|
executable="twist_stamper",
|
||||||
|
remappings=[
|
||||||
|
('/cmd_vel_out', '/ackermann_controller/reference'),
|
||||||
|
],
|
||||||
output='screen'
|
output='screen'
|
||||||
)
|
)
|
||||||
|
|
||||||
@@ -108,6 +117,7 @@ def generate_launch_description():
|
|||||||
ld.add_action(gz_bridge)
|
ld.add_action(gz_bridge)
|
||||||
ld.add_action(joint_state_broadcaster)
|
ld.add_action(joint_state_broadcaster)
|
||||||
ld.add_action(controller)
|
ld.add_action(controller)
|
||||||
|
ld.add_action(twist_stamper)
|
||||||
ld.add_action(rviz2)
|
ld.add_action(rviz2)
|
||||||
|
|
||||||
return ld
|
return ld
|
||||||
|
|||||||
@@ -167,4 +167,4 @@
|
|||||||
</sensor>
|
</sensor>
|
||||||
</gazebo>
|
</gazebo>
|
||||||
</xacro:macro>
|
</xacro:macro>
|
||||||
</robot>
|
</robot>
|
||||||
|
|||||||
@@ -66,7 +66,7 @@
|
|||||||
<mu2>1.2</mu2>
|
<mu2>1.2</mu2>
|
||||||
</ode>
|
</ode>
|
||||||
</friction>
|
</friction>
|
||||||
<soft_cfm>0.01</soft_cfm> <!-- Soft contact to prevent rigid collisions -->
|
<soft_cfm>0.1</soft_cfm> <!-- Soft contact to prevent rigid collisions -->
|
||||||
<soft_erp>0.1</soft_erp> <!-- Error reduction parameter (makes contact softer) -->
|
<soft_erp>0.1</soft_erp> <!-- Error reduction parameter (makes contact softer) -->
|
||||||
</surface>
|
</surface>
|
||||||
</xacro:element>
|
</xacro:element>
|
||||||
@@ -81,4 +81,4 @@
|
|||||||
<origin xyz="${xyz}" rpy="${rpy}"/>
|
<origin xyz="${xyz}" rpy="${rpy}"/>
|
||||||
</joint>
|
</joint>
|
||||||
</xacro:macro>
|
</xacro:macro>
|
||||||
</robot>
|
</robot>
|
||||||
|
|||||||
@@ -25,7 +25,7 @@
|
|||||||
<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.156" rpy="0 0 0" frequency="300"/>
|
||||||
<xacro:ouster_lidar name="lidar" parent="base" xyz="0 0 0.15" rpy="0 0 0" model="vlp16" frequency="10" topic="/points"/>
|
<xacro:ouster_lidar name="lidar" parent="base" xyz="0 0 0.35" rpy="0 0 0" model="OS1" frequency="10" topic="/points"/>
|
||||||
|
|
||||||
<link name="steer_fl_link">
|
<link name="steer_fl_link">
|
||||||
<inertial>
|
<inertial>
|
||||||
@@ -103,4 +103,4 @@
|
|||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
</joint>
|
</joint>
|
||||||
</ros2_control>
|
</ros2_control>
|
||||||
</robot>
|
</robot>
|
||||||
|
|||||||
@@ -20,7 +20,7 @@
|
|||||||
<plugin
|
<plugin
|
||||||
filename="gz-sim-sensors-system"
|
filename="gz-sim-sensors-system"
|
||||||
name="gz::sim::systems::Sensors">
|
name="gz::sim::systems::Sensors">
|
||||||
<render_engine>ogre2</render_engine>
|
<render_engine>ogre</render_engine>
|
||||||
</plugin>
|
</plugin>
|
||||||
<plugin filename="gz-sim-imu-system"
|
<plugin filename="gz-sim-imu-system"
|
||||||
name="gz::sim::systems::Imu">
|
name="gz::sim::systems::Imu">
|
||||||
@@ -92,4 +92,4 @@
|
|||||||
<self_collide>false</self_collide>
|
<self_collide>false</self_collide>
|
||||||
</model>
|
</model>
|
||||||
</world>
|
</world>
|
||||||
</sdf>
|
</sdf>
|
||||||
|
|||||||
112
src/sherpa/worlds/raceway.world
Normal file
112
src/sherpa/worlds/raceway.world
Normal file
@@ -0,0 +1,112 @@
|
|||||||
|
<?xml version="1.0" ?>
|
||||||
|
<sdf version='1.7'>
|
||||||
|
<world name='sonoma'>
|
||||||
|
<scene>
|
||||||
|
<grid>false</grid>
|
||||||
|
</scene>
|
||||||
|
<plugin
|
||||||
|
filename="ignition-gazebo-physics-system"
|
||||||
|
name="ignition::gazebo::systems::Physics">
|
||||||
|
</plugin>
|
||||||
|
<plugin
|
||||||
|
filename="ignition-gazebo-sensors-system"
|
||||||
|
name="ignition::gazebo::systems::Sensors">
|
||||||
|
<render_engine>ogre2</render_engine>
|
||||||
|
</plugin>
|
||||||
|
<plugin
|
||||||
|
filename="ignition-gazebo-user-commands-system"
|
||||||
|
name="ignition::gazebo::systems::UserCommands">
|
||||||
|
</plugin>
|
||||||
|
<plugin
|
||||||
|
filename="ignition-gazebo-scene-broadcaster-system"
|
||||||
|
name="ignition::gazebo::systems::SceneBroadcaster">
|
||||||
|
</plugin>
|
||||||
|
|
||||||
|
<gui fullscreen="0">
|
||||||
|
|
||||||
|
<!-- 3D scene -->
|
||||||
|
<plugin filename="GzScene3D" name="3D View">
|
||||||
|
<ignition-gui>
|
||||||
|
<title>3D View</title>
|
||||||
|
<property type="bool" key="showTitleBar">false</property>
|
||||||
|
<property type="string" key="state">docked</property>
|
||||||
|
</ignition-gui>
|
||||||
|
|
||||||
|
<engine>ogre2</engine>
|
||||||
|
<scene>scene</scene>
|
||||||
|
<ambient_light>0.4 0.4 0.4</ambient_light>
|
||||||
|
<background_color>0.5 0.8 0.95</background_color>
|
||||||
|
<!--camera_pose>276.46 -130.36 5.27 0 0.43 -1.24</camera_pose-->
|
||||||
|
<camera_follow>
|
||||||
|
<target>prius_hybrid</target>
|
||||||
|
<p_gain>0.5</p_gain>
|
||||||
|
<offset>0.5 5 2</offset>
|
||||||
|
</camera_follow>
|
||||||
|
</plugin>
|
||||||
|
|
||||||
|
<!-- World control -->
|
||||||
|
<plugin filename="WorldControl" name="World control">
|
||||||
|
<ignition-gui>
|
||||||
|
<title>World control</title>
|
||||||
|
<property type="bool" key="showTitleBar">false</property>
|
||||||
|
<property type="bool" key="resizable">false</property>
|
||||||
|
<property type="double" key="height">72</property>
|
||||||
|
<property type="double" key="width">121</property>
|
||||||
|
<property type="double" key="z">1</property>
|
||||||
|
|
||||||
|
<property type="string" key="state">floating</property>
|
||||||
|
<anchors target="3D View">
|
||||||
|
<line own="left" target="left"/>
|
||||||
|
<line own="bottom" target="bottom"/>
|
||||||
|
</anchors>
|
||||||
|
</ignition-gui>
|
||||||
|
|
||||||
|
<play_pause>true</play_pause>
|
||||||
|
<step>true</step>
|
||||||
|
<start_paused>true</start_paused>
|
||||||
|
|
||||||
|
</plugin>
|
||||||
|
|
||||||
|
<!-- World statistics -->
|
||||||
|
<plugin filename="WorldStats" name="World stats">
|
||||||
|
<ignition-gui>
|
||||||
|
<title>World stats</title>
|
||||||
|
<property type="bool" key="showTitleBar">false</property>
|
||||||
|
<property type="bool" key="resizable">false</property>
|
||||||
|
<property type="double" key="height">110</property>
|
||||||
|
<property type="double" key="width">290</property>
|
||||||
|
<property type="double" key="z">1</property>
|
||||||
|
|
||||||
|
<property type="string" key="state">floating</property>
|
||||||
|
<anchors target="3D View">
|
||||||
|
<line own="right" target="right"/>
|
||||||
|
<line own="bottom" target="bottom"/>
|
||||||
|
</anchors>
|
||||||
|
</ignition-gui>
|
||||||
|
|
||||||
|
<sim_time>true</sim_time>
|
||||||
|
<real_time>true</real_time>
|
||||||
|
<real_time_factor>true</real_time_factor>
|
||||||
|
<iterations>true</iterations>
|
||||||
|
</plugin>
|
||||||
|
|
||||||
|
<plugin filename="ImageDisplay" name="dis">
|
||||||
|
<ignition-gui>
|
||||||
|
<property key="state" type="string">docked</property>
|
||||||
|
</ignition-gui>
|
||||||
|
<topic>front_camera</topic>
|
||||||
|
</plugin>
|
||||||
|
|
||||||
|
<plugin filename="Teleop" name="Teleop">
|
||||||
|
<ignition-gui>
|
||||||
|
<property type="string" key="state">docked</property>
|
||||||
|
</ignition-gui>
|
||||||
|
<topic>/cmd_vel</topic>
|
||||||
|
</plugin>
|
||||||
|
</gui>
|
||||||
|
<include>
|
||||||
|
<uri>https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Sonoma Raceway</uri>
|
||||||
|
</include>
|
||||||
|
|
||||||
|
</world>
|
||||||
|
</sdf>
|
||||||
Reference in New Issue
Block a user