Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Submitted models/marble hd2 sensor config 3 #516

Closed
wants to merge 14 commits into from
Closed
Show file tree
Hide file tree
Changes from 12 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
13 changes: 13 additions & 0 deletions submitted_models/marble_hd2_sensor_config_3/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
cmake_minimum_required(VERSION 2.8.3)
project(marble_hd2_sensor_config_3)

find_package(catkin REQUIRED)

catkin_package()

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

install(FILES model.sdf model.config
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})

Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
<?xml version="1.0"?>
<launch>
<arg name="name" doc="Name of Vehicle"/>
<param name="$(arg name)/robot_description" command="$(find xacro)/xacro '$(find marble_hd2_sensor_config_3)/urdf/robot_from_sdf.xacro' name:=$(arg name)"/>
</launch>

169 changes: 169 additions & 0 deletions submitted_models/marble_hd2_sensor_config_3/launch/example.ign
Original file line number Diff line number Diff line change
@@ -0,0 +1,169 @@
<?xml version="1.0"?>
<!-- Usage: ign launch path/to/example.ign robotName:=<X1>

Parameters:
robotName: Name to be assigned to model
-->

<%
require_relative 'spawner'

# Modify these as needed
$enableGroundTruth = true
$headless = local_variables.include?(:headless) ? :headless : false

%>

<%
unless local_variables.include?(:robotName)
raise "missing parameters. robotName is a required parameter"
end

# This assumes that this launch file is in a directory below the model
modelURI = File.expand_path("../", File.dirname(__FILE__))
$worldName = 'example'
worldFile = File.join(File.expand_path("../worlds", File.dirname(__FILE__)), "#{$worldName}.sdf")

%>

<ignition version='1.0'>
<env>
<name>IGN_GAZEBO_SYSTEM_PLUGIN_PATH</name>
<value>$LD_LIBRARY_PATH</value>
</env>

<!-- Start ROS first. This is a bit hacky for now. -->
<!-- Make sure to source /opt/ros/melodic/setup.bash -->
<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>

<plugin name="ignition::launch::GazeboServer"
filename="libignition-launch-gazebo.so">
<world_file><%= worldFile %></world_file>
<run>true</run>
<levels>false</levels>
<record>
<enabled>false</enabled>
</record>

<plugin entity_name="<%= $worldName %>"
entity_type="world"
filename="libignition-gazebo-physics-system.so"
name="ignition::gazebo::systems::Physics">
</plugin>

<plugin entity_name="<%= $worldName %>"
entity_type="world"
filename="libignition-gazebo-sensors-system.so"
name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
<plugin entity_name="<%= $worldName %>"
entity_type="world"
filename="libignition-gazebo-user-commands-system.so"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin entity_name="<%= $worldName %>"
entity_type="world"
filename="libignition-gazebo-scene-broadcaster-system.so"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>
<plugin entity_name="<%= $worldName %>"
entity_type="world"
filename="libignition-gazebo-imu-system.so"
name="ignition::gazebo::systems::Imu">
</plugin>

<plugin entity_name="<%= $worldName %>"
entity_type="world"
filename="libignition-gazebo-magnetometer-system.so"
name="ignition::gazebo::systems::Magnetometer">
</plugin>

<plugin entity_name="<%= $worldName %>"
entity_type="world"
filename="libignition-gazebo-air-pressure-system.so"
name="ignition::gazebo::systems::AirPressure">
</plugin>
</plugin>

<%if !$headless %>
<executable_wrapper>
<plugin name="ignition::launch::GazeboGui"
filename="libignition-launch-gazebogui.so">
<world_name><%= $worldName %></world_name>
<window_title>SubT Simulator</window_title>
<window_icon><%= ENV['SUBT_IMAGES_PATH'] %>/SubT_logo.svg</window_icon>
<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.2 0.2 0.1</ambient_light>
<background_color>0.8 0.8 0.8</background_color>
<camera_pose>-6.3 -4.2 3.6 0 0.268 0.304</camera_pose>
<service>/world/<%= $worldName %>/scene/info</service>
<pose_topic>/world/<%= $worldName %>/pose/info</pose_topic>
<scene_topic>/world/<%= $worldName %>/scene/info</scene_topic>
<deletion_topic>/world/<%= $worldName %>/scene/deletion</deletion_topic>
</plugin>
<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>
<service>/world/<%= $worldName %>/control</service>
<stats_topic>/world/<%= $worldName %>/stats</stats_topic>

</plugin>

<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>
<topic>/world/<%= $worldName %>/stats</topic>
</plugin>
</plugin>
</executable_wrapper>
<%end%>

<%= spawner(robotName, modelURI, $worldName, 0, 0, 0, 0, 0, 0) %>
<%= rosExecutables(robotName, $worldName) %>

</ignition>

96 changes: 96 additions & 0 deletions submitted_models/marble_hd2_sensor_config_3/launch/spawner.rb
Original file line number Diff line number Diff line change
@@ -0,0 +1,96 @@
def spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw)
<<-HEREDOC
<spawn name='#{_name}'>
<name>#{_name}</name>
<allow_renaming>false</allow_renaming>
<pose>#{_x} #{_y} #{_z + 0.2} #{_roll} #{_pitch} #{_yaw}</pose>
<world>#{_worldName}</world>
<is_performer>true</is_performer>
<sdf version='1.6'>
<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>
<topic>/model/#{_name}/cmd_vel_relay</topic>
<min_velocity>-1</min_velocity>
<max_velocity>1</max_velocity>
Comment on lines +27 to +28
Copy link
Contributor

Choose a reason for hiding this comment

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

These velocities seem pretty low - are these the correct values, or should they be higher?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Owing to COVID-19 we do not have validation data. I will ask MARBLE if that has changed in the past couple weeks. Those were the values assigned in leu of not having validation data.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Owing to COVID-19 we do not have validation data. I will ask MARBLE if that has changed in the past couple weeks. Those were the values assigned in leu of not having validation data.

Copy link
Contributor

Choose a reason for hiding this comment

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

The HD2 model will continue to have 1 m/s maximum velocity (matching X1 and Husky) until validation can be provided. Matching the speed to the most similar pre-existing model avoids any new model having a speed advantage that has not been validated.

<min_acceleration>-3</min_acceleration>
<max_acceleration>3</max_acceleration>
</plugin>
<!-- Publish robot state information -->
<plugin filename="libignition-gazebo-pose-publisher-system.so"
name="ignition::gazebo::systems::PosePublisher">
<publish_link_pose>true</publish_link_pose>
<publish_sensor_pose>true</publish_sensor_pose>
<publish_collision_pose>false</publish_collision_pose>
<publish_visual_pose>false</publish_visual_pose>
<publish_nested_model_pose>#{$enableGroundTruth}</publish_nested_model_pose>
<use_pose_vector_msg>true</use_pose_vector_msg>
<static_publisher>true</static_publisher>
<static_update_frequency>1</static_update_frequency>
</plugin>
<!-- Battery plugin -->
<plugin filename="libignition-gazebo-linearbatteryplugin-system.so"
name="ignition::gazebo::systems::LinearBatteryPlugin">
<battery_name>linear_battery</battery_name>
<voltage>12.694</voltage>
<open_circuit_voltage_constant_coef>12.694</open_circuit_voltage_constant_coef>
<open_circuit_voltage_linear_coef>-3.1424</open_circuit_voltage_linear_coef>
<initial_charge>78.4</initial_charge>
<capacity>78.4</capacity>
<resistance>0.061523</resistance>
<smooth_current_tau>1.9499</smooth_current_tau>
<power_load>9.9</power_load>
<start_on_motion>true</start_on_motion>
</plugin>
<!-- Gas Sensor plugin -->
<plugin filename="libGasEmitterDetectorPlugin.so"
name="subt::GasDetector">
<topic>/model/#{_name}/gas_detected</topic>
<update_rate>10</update_rate>
<type>gas</type>
</plugin>
<plugin filename="libignition-gazebo-breadcrumbs-system.so"
name="ignition::gazebo::systems::Breadcrumbs">
<topic>/model/#{_name}/breadcrumb/deploy</topic>
<max_deployments>12</max_deployments>
<disable_physics_time>3.0</disable_physics_time>
<breadcrumb>
<sdf version="1.6">
<model name="#{_name}__breadcrumb__">
<pose>-0.45 0 0 0 0 0</pose>
<include>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Breadcrumb Node</uri>
</include>
</model>
</sdf>
</breadcrumb>
</plugin>
</include>
</sdf>
</spawn>
HEREDOC
end

def rosExecutables(_name, _worldName)
<<-HEREDOC
<executable name='robot_description'>
<command>roslaunch --wait marble_hd2_sensor_config_3 description.launch world_name:=#{_worldName} name:=#{_name}</command>
</executable>
<executable name='topics'>
<command>roslaunch --wait marble_hd2_sensor_config_3 vehicle_topics.launch world_name:=#{_worldName} name:=#{_name} breadcrumbs:=1</command>
</executable>
HEREDOC
end
Loading