Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion submitted_models/coro_hd2_sensor_config_1/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ find_package(catkin REQUIRED)

catkin_package()

install(DIRECTORY launch meshes materials urdf
install(DIRECTORY launch meshes materials urdf worlds
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})

install(FILES model.sdf model.config
Expand Down
19 changes: 13 additions & 6 deletions submitted_models/coro_hd2_sensor_config_1/launch/example.ign
Original file line number Diff line number Diff line change
Expand Up @@ -6,16 +6,17 @@
-->

<%
require_relative 'spawner'
#require_relative 'spawner'
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is #require_relative 'spawner' not working?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It does for coro_hd2_sc1, but not when this file is transitively included from coro_hd2_sc2

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Got it.

_base_dir = defined?(base_dir) ? base_dir.tr('"', '') : File.realpath(File.join(File.dirname(__FILE__), ".."))
load File.join(_base_dir, "launch", "spawner.rb")
# Modify these as needed
$enableGroundTruth = true
$headless = false
$headless = local_variables.include?(:headless) ? :headless : false
%>

<%
unless local_variables.include?(:robotName)
raise "missing parameters. robotName is a required parameter"
end
Expand All @@ -35,9 +36,11 @@

<!-- Start ROS first. This is a bit hacky for now. -->
<!-- Make sure to source /opt/ros/melodic/setup.bash -->
<% if local_variables.include?(:ros) and ros %>
<executable name='ros'>
<command>roslaunch subt_ros competition_init.launch world_name:=<%=$worldName%> vehicle_topics:=0 enable_ground_truth:=<%=($enableGroundTruth)?"1":"0"%> robot_names:=<%=robotName%></command>
</executable>
<% end %>

<plugin name="ignition::launch::GazeboServer"
filename="libignition-launch-gazebo.so">
Expand Down Expand Up @@ -163,9 +166,13 @@
</executable_wrapper>
<%end%>

<plugin name="ignition::launch::GazeboFactory" filename="libignition-launch-gazebo-factory.so">
<%= spawner(robotName, modelURI, $worldName, 0, 0, 0, 0, 0, 0) %>
<plugin name="ignition::launch::GazeboFactory"
filename="ignition-launch-gazebo-factory">
<%= spawner(robotName, modelURI, $worldName, 0, 0, 0, 0, 0, 0) %>
</plugin>
<%= rosExecutables(robotName, $worldName) %>
<% if local_variables.include?(:ros) and ros %>
<%= rosExecutables(robotName, $worldName) %>
<% end %>

</ignition>

84 changes: 15 additions & 69 deletions submitted_models/coro_hd2_sensor_config_1/launch/spawner.rb
Original file line number Diff line number Diff line change
Expand Up @@ -10,24 +10,20 @@ def spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw)
<include>
<name>#{_name}</name>
<uri>#{_modelURI}</uri>
<!-- Diff drive -->
<plugin filename="libignition-gazebo-diff-drive-system.so"
name="ignition::gazebo::systems::DiffDrive">
<left_joint>front_left_wheel_joint</left_joint>
<left_joint>front_middle_left_wheel_joint</left_joint>
<left_joint>rear_middle_left_wheel_joint</left_joint>
<left_joint>rear_left_wheel_joint</left_joint>
<right_joint>front_right_wheel_joint</right_joint>
<right_joint>front_middle_right_wheel_joint</right_joint>
<right_joint>rear_middle_right_wheel_joint</right_joint>
<right_joint>rear_right_wheel_joint</right_joint>
<wheel_separation>#{0.525}</wheel_separation>
<wheel_radius>0.129</wheel_radius>
<!-- Tracked vehicle controller -->
<plugin name="ignition::gazebo::systems::TrackedVehicle" filename="ignition-gazebo-tracked-vehicle-system">
<left_track><link>left_track</link></left_track>
<right_track><link>right_track</link></right_track>
<tracks_separation>#{0.525}</tracks_separation>
<tracks_height>0.258</tracks_height>
<steering_efficiency>0.5</steering_efficiency>
<topic>/model/#{_name}/cmd_vel_relay</topic>
<min_velocity>-1</min_velocity>
<max_velocity>1</max_velocity>
<min_acceleration>-3</min_acceleration>
<max_acceleration>3</max_acceleration>
<linear_velocity>
<min_velocity>-1</min_velocity>
<max_velocity>1</max_velocity>
<min_acceleration>-3</min_acceleration>
<max_acceleration>3</max_acceleration>
</linear_velocity>
</plugin>
<!-- Publish robot state information -->
<plugin filename="libignition-gazebo-pose-publisher-system.so"
Expand All @@ -54,6 +50,8 @@ def spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw)
<smooth_current_tau>1.9499</smooth_current_tau>
<power_load>9.9</power_load>
<start_on_motion>true</start_on_motion>
<power_draining_topic>/model/#{_name}/link/left_track/track_cmd_vel</power_draining_topic>
<power_draining_topic>/model/#{_name}/link/right_track/track_cmd_vel</power_draining_topic>
</plugin>
<!-- Gas Sensor plugin -->
<plugin filename="libGasEmitterDetectorPlugin.so"
Expand All @@ -62,58 +60,6 @@ def spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw)
<update_rate>10</update_rate>
<type>gas</type>
</plugin>
<!-- Wheel slip -->
<plugin filename="libignition-gazebo-wheel-slip-system.so"
name="ignition::gazebo::systems::WheelSlip">
<wheel link_name="front_left_wheel_link">
<slip_compliance_lateral>0.086</slip_compliance_lateral>
<slip_compliance_longitudinal>0</slip_compliance_longitudinal>
<wheel_normal_force>41.47103925</wheel_normal_force>
<wheel_radius>0.129</wheel_radius>
</wheel>
<wheel link_name="front_middle_left_wheel_link">
<slip_compliance_lateral>0.086</slip_compliance_lateral>
<slip_compliance_longitudinal>0</slip_compliance_longitudinal>
<wheel_normal_force>41.47103925</wheel_normal_force>
<wheel_radius>0.129</wheel_radius>
</wheel>
<wheel link_name="rear_middle_left_wheel_link">
<slip_compliance_lateral>0.086</slip_compliance_lateral>
<slip_compliance_longitudinal>0</slip_compliance_longitudinal>
<wheel_normal_force>41.47103925</wheel_normal_force>
<wheel_radius>0.129</wheel_radius>
</wheel>
<wheel link_name="rear_left_wheel_link">
<slip_compliance_lateral>0.086</slip_compliance_lateral>
<slip_compliance_longitudinal>0.25</slip_compliance_longitudinal>
<wheel_normal_force>41.47103925</wheel_normal_force>
<wheel_radius>0.129</wheel_radius>
</wheel>
<wheel link_name="front_right_wheel_link">
<slip_compliance_lateral>0.086</slip_compliance_lateral>
<slip_compliance_longitudinal>0</slip_compliance_longitudinal>
<wheel_normal_force>41.47103925</wheel_normal_force>
<wheel_radius>0.129</wheel_radius>
</wheel>
<wheel link_name="front_middle_right_wheel_link">
<slip_compliance_lateral>0.086</slip_compliance_lateral>
<slip_compliance_longitudinal>0</slip_compliance_longitudinal>
<wheel_normal_force>41.47103925</wheel_normal_force>
<wheel_radius>0.129</wheel_radius>
</wheel>
<wheel link_name="rear_middle_right_wheel_link">
<slip_compliance_lateral>0.086</slip_compliance_lateral>
<slip_compliance_longitudinal>0</slip_compliance_longitudinal>
<wheel_normal_force>41.47103925</wheel_normal_force>
<wheel_radius>0.129</wheel_radius>
</wheel>
<wheel link_name="rear_right_wheel_link">
<slip_compliance_lateral>0.086</slip_compliance_lateral>
<slip_compliance_longitudinal>0</slip_compliance_longitudinal>
<wheel_normal_force>41.47103925</wheel_normal_force>
<wheel_radius>0.129</wheel_radius>
</wheel>
</plugin>
</include>
</sdf>
</spawn>
Expand Down
Loading