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
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ def spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw)
<spawn name="#{_name}">
<name>#{_name}</name>
<allow_renaming>false</allow_renaming>
<pose>#{_x} #{_y} #{_z + -0.03} #{_roll} #{_pitch} #{_yaw}</pose>
<pose>#{_x} #{_y} #{_z + -0.02} #{_roll} #{_pitch} #{_yaw}</pose>
<world>#{_worldName}</world>
<is_performer>true</is_performer>
<sdf version='1.6'>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ def spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw)
<spawn name='#{_name}'>
<name>#{_name}</name>
<allow_renaming>false</allow_renaming>
<pose>#{_x} #{_y} #{_z + 0.21} #{_roll} #{_pitch} #{_yaw}</pose>
<pose>#{_x} #{_y} #{_z + 0.061} #{_roll} #{_pitch} #{_yaw}</pose>
<world>#{_worldName}</world>
<is_performer>true</is_performer>
<sdf version='1.6'>
Expand Down
97 changes: 83 additions & 14 deletions submitted_models/coro_karen_sensor_config_1/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -14,21 +14,19 @@
<izz>9.733</izz>
</inertia>
</inertial>

<collision name="chassis_collision">
<pose>0 0 0.25 0 0 0</pose>
<collision name="tower_collision">
<pose>0.37 0 0.45625 0 0 0</pose>
<geometry>
<box>
<size>1.1 0.7 0.4</size>
<size>0.2 0.2 0.4125</size>
</box>
</geometry>
</collision>

<collision name="tower_collision">
<pose>0.13 0 0.27 0 0 0</pose>
<collision name="chassis_main_collision">
<pose>0 0 0.15 0 0 0</pose>
<geometry>
<box>
<size>0.2 0.2 0.34</size>
<size>1.0 0.45 0.2</size>
</box>
</geometry>
</collision>
Expand All @@ -47,6 +45,15 @@
<diffuse>0.9411764705882353 0.9411764705882353 0.9411764705882353 1</diffuse>
</material>
</visual>
<collision name="front_side_collision">
<pose>0.5 0 0.3 1.5707 0 0</pose>
<geometry>
<cylinder>
<radius>0.07</radius>
<length>0.55</length>
</cylinder>
</geometry>
</collision>

<visual name="front_side">
<pose>0.5 0 0.3 1.5707 0 0</pose>
Expand All @@ -61,7 +68,15 @@
<diffuse>0.39215686274509803 0.39215686274509803 0.9215686274509803 1</diffuse>
</material>
</visual>

<collision name="back_side_collision">
<pose>-0.5 0 0.3 1.5707 0 0</pose>
<geometry>
<cylinder>
<radius>0.07</radius>
<length>0.55</length>
</cylinder>
</geometry>
</collision>
<visual name="back_side">
<pose>-0.5 0 0.3 1.5707 0 0</pose>
<geometry>
Expand All @@ -75,7 +90,15 @@
<diffuse>0.39215686274509803 0.39215686274509803 0.9215686274509803 1</diffuse>
</material>
</visual>

<collision name="left_side_collision">
<pose>0 0.25 0.3 0 1.5707 0</pose>
<geometry>
<cylinder>
<radius>0.07</radius>
<length>1.0</length>
</cylinder>
</geometry>
</collision>
<visual name="left_side">
<pose>0 0.25 0.3 0 1.5707 0</pose>
<geometry>
Expand All @@ -89,7 +112,15 @@
<diffuse>0.39215686274509803 0.39215686274509803 0.9215686274509803 1</diffuse>
</material>
</visual>

<collision name="right_side_collision">
<pose>0 -0.25 0.3 0 1.5707 0</pose>
<geometry>
<cylinder>
<radius>0.07</radius>
<length>1.0</length>
</cylinder>
</geometry>
</collision>
<visual name="right_side">
<pose>0 -0.25 0.3 0 1.5707 0</pose>
<geometry>
Expand All @@ -103,8 +134,15 @@
<diffuse>0.39215686274509803 0.39215686274509803 0.9215686274509803 1</diffuse>
</material>
</visual>


<collision name="differential_collision">
<pose>-0.5 0 0.0 1.5707 0 0</pose>
<geometry>
<cylinder>
<radius>0.06</radius>
<length>0.44</length>
</cylinder>
</geometry>
</collision>
<visual name="differential_visual">
<pose>-0.5 0 0.0 1.5707 0 0</pose>
<geometry>
Expand Down Expand Up @@ -880,7 +918,14 @@
<direction>0 -1 0</direction>
<cast_shadows>1</cast_shadows>
</light>

<collision name="light_front_left_collision">
<pose>0.44 0.23 0.41 0 0 0.75</pose>
<geometry>
<box>
<size>0.01 0.12 0.08</size>
</box>
</geometry>
</collision>
<visual name="light_front_left_visual">
<pose>0.44 0.23 0.41 0 0 0.75</pose>
<geometry>
Expand All @@ -893,6 +938,14 @@
<diffuse>1.0 1.0 1.0 1.0</diffuse>
</material>
</visual>
<collision name="light_front_right_collision">
<pose>0.44 -0.23 0.41 0 0 -0.75</pose>
<geometry>
<box>
<size>0.01 0.12 0.08</size>
</box>
</geometry>
</collision>
<visual name="light_front_right_visual">
<pose>0.44 -0.23 0.41 0 0 -0.75</pose>
<geometry>
Expand All @@ -905,6 +958,14 @@
<diffuse>1.0 1.0 1.0 1.0</diffuse>
</material>
</visual>
<collision name="light_rear_left_collision">
<pose>-0.3 0.25 0.41 0 0 -0.75</pose>
<geometry>
<box>
<size>0.01 0.12 0.08</size>
</box>
</geometry>
</collision>
<visual name="light_rear_left_visual">
<pose>-0.3 0.25 0.41 0 0 -0.75</pose>
<geometry>
Expand All @@ -917,6 +978,14 @@
<diffuse>1.0 1.0 1.0 1.0</diffuse>
</material>
</visual>
<collision name="light_rear_right_collision">
<pose>-0.3 -0.25 0.41 0 0 0.75</pose>
<geometry>
<box>
<size>0.01 0.12 0.08</size>
</box>
</geometry>
</collision>
<visual name="light_rear_right_visual">
<pose>-0.3 -0.25 0.41 0 0 0.75</pose>
<geometry>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ def spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw)
<spawn name='#{_name}'>
<name>#{_name}</name>
<allow_renaming>false</allow_renaming>
<pose>#{_x} #{_y} #{_z + 0.21} #{_roll} #{_pitch} #{_yaw}</pose>
<pose>#{_x} #{_y} #{_z + 0.187} #{_roll} #{_pitch} #{_yaw}</pose>
<world>#{_worldName}</world>
<is_performer>true</is_performer>
<sdf version='1.6'>
Expand Down
4 changes: 4 additions & 0 deletions subt_ign/include/subt_ign/RobotPlatformTypes.hh
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ const std::vector<std::string> robotPlatformTypes = {
"ALLIE",
"ANYMAL_B",
"ANYMAL_C",
"CRYSTAL",
"DS1",
"DTR",
"FREYJA",
Expand All @@ -32,14 +33,17 @@ const std::vector<std::string> robotPlatformTypes = {
"HUSKY",
"KAREN",
"KLOUBAK",
"LILY",
"M100",
"MARV",
"MIKE",
"OZBOT_ATR",
"PAM",
"QAV500",
"R2",
"R3",
"RMF",
"ROCKY",
"SHAFTER",
"SPOT",
"TEAMBASE",
Expand Down
26 changes: 19 additions & 7 deletions subt_ign/launch/cloudsim_sim.ign
Original file line number Diff line number Diff line change
Expand Up @@ -127,28 +127,40 @@
"X1" => "base_link",
"EXPLORER_X1" => "base_link",
"EXPLORER_R2" => "Rear_Rocker_Link",
"CSIRO_DATA61_OZBOT_ATR" => "base_link"
"CSIRO_DATA61_OZBOT_ATR" => "base_link",
"CORO_ALLIE" => "base_link",
"CORO_KAREN" => "base_link",
"CORO_MIKE" => "base_link",
}

MARSUPIAL_VALID_ROBOT_PAIRS = {
"X1" => ["X3", "MARBLE_QAV500", "CERBERUS_GAGARIN", "CERBERUS_RMF", "COSTAR_SHAFTER", "CORO_PAM", "CTU_CRAS_NORLAB_X500"],
"EXPLORER_X1" =>["X3", "MARBLE_QAV500", "CERBERUS_GAGARIN", "CERBERUS_RMF", "COSTAR_SHAFTER", "CORO_PAM", "CTU_CRAS_NORLAB_X500"],
"EXPLORER_R2" =>["X3", "X4", "SSCI_X4", "SOPHISTICATED_ENGINEERING_X4", "EXPLORER_DS1", "MARBLE_QAV500", "CERBERUS_M100", "CERBERUS_GAGARIN", "CERBERUS_RMF", "COSTAR_SHAFTER", "CORO_PAM", "CTU_CRAS_NORLAB_X500"],
"CSIRO_DATA61_OZBOT_ATR" =>["X3", "X4", "SSCI_X4", "SOPHISTICATED_ENGINEERING_X4","EXPLORER_DS1", "MARBLE_QAV500", "CERBERUS_M100", "CERBERUS_GAGARIN", "CERBERUS_RMF", "COSTAR_SHAFTER", "CORO_PAM", "CTU_CRAS_NORLAB_X500"]
"X1" => ["X3", "MARBLE_QAV500", "CERBERUS_GAGARIN", "CERBERUS_RMF", "COSTAR_SHAFTER", "CORO_PAM", "CTU_CRAS_NORLAB_X500", "CORO_CRYSTAL"],
"CORO_ALLIE" => ["CERBERUS_RMF", "CORO_CRYSTAL"],
"CORO_KAREN" => ["CERBERUS_RMF", "CORO_PAM", "CTU_CRAS_NORLAB_X500","CORO_CRYSTAL"],
"CORO_MIKE" => ["X3", "X4", "SSCI_X4", "SOPHISTICATED_ENGINEERING_X4", "CERBERUS_M100", "CERBERUS_GAGARIN", "CERBERUS_RMF", "COSTAR_SHAFTER", "CORO_PAM", "CTU_CRAS_NORLAB_X500", "CORO_CRYSTAL"],
"EXPLORER_X1" =>["X3", "MARBLE_QAV500", "CERBERUS_GAGARIN", "CERBERUS_RMF", "COSTAR_SHAFTER", "CORO_PAM", "CTU_CRAS_NORLAB_X500", "CORO_CRYSTAL"],
"EXPLORER_R2" => ["X3", "X4", "SSCI_X4", "SOPHISTICATED_ENGINEERING_X4", "EXPLORER_DS1", "MARBLE_QAV500", "CERBERUS_M100", "CERBERUS_GAGARIN", "CERBERUS_RMF", "COSTAR_SHAFTER", "CORO_PAM", "CTU_CRAS_NORLAB_X500", "CORO_CRYSTAL"],
"CSIRO_DATA61_OZBOT_ATR" =>["X3", "X4", "SSCI_X4", "SOPHISTICATED_ENGINEERING_X4","EXPLORER_DS1", "MARBLE_QAV500", "CERBERUS_M100", "CERBERUS_GAGARIN", "CERBERUS_RMF", "COSTAR_SHAFTER", "CORO_PAM", "CTU_CRAS_NORLAB_X500", "CORO_CRYSTAL"]
}

MARSUPIAL_PARENT_ROBOT_POSITION_OFFSETS = {
"X1" => Vector3d.new(0, 0, 0.717),
"EXPLORER_X1" => Vector3d.new(0, 0, 0.717),
"EXPLORER_R2" => Vector3d.new(-0.402375, 0, 0.6874),
"CSIRO_DATA61_OZBOT_ATR" => Vector3d.new(-0.15, 0, 0.528)
"CSIRO_DATA61_OZBOT_ATR" => Vector3d.new(-0.15, 0, 0.528),
"CORO_ALLIE" => Vector3d.new(-0.18, 0, 0.320),
"CORO_KAREN" => Vector3d.new(-0.18, 0, 0.5),
"CORO_MIKE" => Vector3d.new(-0.2, 0, 0.5775)
}

MARSUPIAL_PARENT_ROBOT_ROTATION_OFFSETS = {
"X1" => AngularVector3d.new(0, 0, 0),
"EXPLORER_X1" => AngularVector3d.new(0, 0, 0),
"EXPLORER_R2" => AngularVector3d.new(0, 0, -3.1416),
"CSIRO_DATA61_OZBOT_ATR" => AngularVector3d.new(0, 0, -3.1416)
"CSIRO_DATA61_OZBOT_ATR" => AngularVector3d.new(0, 0, -3.1416),
"CORO_ALLIE" => AngularVector3d.new(0, 0, 0),
"CORO_KAREN" => AngularVector3d.new(0, 0, 0),
"CORO_MIKE" => AngularVector3d.new(0, 0, 0)
}

allExecutables = ""
Expand Down
26 changes: 19 additions & 7 deletions subt_ign/launch/competition.ign
Original file line number Diff line number Diff line change
Expand Up @@ -123,28 +123,40 @@
"X1" => "base_link",
"EXPLORER_X1" => "base_link",
"EXPLORER_R2" => "Rear_Rocker_Link",
"CSIRO_DATA61_OZBOT_ATR" => "base_link"
"CSIRO_DATA61_OZBOT_ATR" => "base_link",
"CORO_ALLIE" => "base_link",
"CORO_KAREN" => "base_link",
"CORO_MIKE" => "base_link",
}

MARSUPIAL_VALID_ROBOT_PAIRS = {
"X1" => ["X3", "MARBLE_QAV500", "CERBERUS_GAGARIN", "CERBERUS_RMF", "COSTAR_SHAFTER", "CORO_PAM", "CTU_CRAS_NORLAB_X500"],
"EXPLORER_X1" =>["X3", "MARBLE_QAV500", "CERBERUS_GAGARIN", "CERBERUS_RMF", "COSTAR_SHAFTER", "CORO_PAM", "CTU_CRAS_NORLAB_X500"],
"EXPLORER_R2" =>["X3", "X4", "SSCI_X4", "SOPHISTICATED_ENGINEERING_X4", "EXPLORER_DS1", "MARBLE_QAV500", "CERBERUS_M100", "CERBERUS_GAGARIN", "CERBERUS_RMF", "COSTAR_SHAFTER", "CORO_PAM", "CTU_CRAS_NORLAB_X500"],
"CSIRO_DATA61_OZBOT_ATR" =>["X3", "X4", "SSCI_X4", "SOPHISTICATED_ENGINEERING_X4","EXPLORER_DS1", "MARBLE_QAV500", "CERBERUS_M100", "CERBERUS_GAGARIN", "CERBERUS_RMF", "COSTAR_SHAFTER", "CORO_PAM", "CTU_CRAS_NORLAB_X500"]
"X1" => ["X3", "MARBLE_QAV500", "CERBERUS_GAGARIN", "CERBERUS_RMF", "COSTAR_SHAFTER", "CORO_PAM", "CTU_CRAS_NORLAB_X500", "CORO_CRYSTAL"],
"CORO_ALLIE" => ["CERBERUS_RMF", "CORO_CRYSTAL"],
"CORO_KAREN" => ["CERBERUS_RMF", "CORO_PAM", "CTU_CRAS_NORLAB_X500","CORO_CRYSTAL"],
"CORO_MIKE" => ["X3", "X4", "SSCI_X4", "SOPHISTICATED_ENGINEERING_X4", "CERBERUS_M100", "CERBERUS_GAGARIN", "CERBERUS_RMF", "COSTAR_SHAFTER", "CORO_PAM", "CTU_CRAS_NORLAB_X500", "CORO_CRYSTAL"],
"EXPLORER_X1" =>["X3", "MARBLE_QAV500", "CERBERUS_GAGARIN", "CERBERUS_RMF", "COSTAR_SHAFTER", "CORO_PAM", "CTU_CRAS_NORLAB_X500", "CORO_CRYSTAL"],
"EXPLORER_R2" =>["X3", "X4", "SSCI_X4", "SOPHISTICATED_ENGINEERING_X4", "EXPLORER_DS1", "MARBLE_QAV500", "CERBERUS_M100", "CERBERUS_GAGARIN", "CERBERUS_RMF", "COSTAR_SHAFTER", "CORO_PAM", "CTU_CRAS_NORLAB_X500", "CORO_CRYSTAL"],
"CSIRO_DATA61_OZBOT_ATR" =>["X3", "X4", "SSCI_X4", "SOPHISTICATED_ENGINEERING_X4","EXPLORER_DS1", "MARBLE_QAV500", "CERBERUS_M100", "CERBERUS_GAGARIN", "CERBERUS_RMF", "COSTAR_SHAFTER", "CORO_PAM", "CTU_CRAS_NORLAB_X500", "CORO_CRYSTAL"]
}

MARSUPIAL_PARENT_ROBOT_POSITION_OFFSETS = {
"X1" => Vector3d.new(0, 0, 0.717),
"EXPLORER_X1" => Vector3d.new(0, 0, 0.717),
"EXPLORER_R2" => Vector3d.new(-0.402375, 0, 0.6874),
"CSIRO_DATA61_OZBOT_ATR" => Vector3d.new(-0.15, 0, 0.528)
"CSIRO_DATA61_OZBOT_ATR" => Vector3d.new(-0.15, 0, 0.528),
"CORO_ALLIE" => Vector3d.new(-0.18, 0, 0.320),
"CORO_KAREN" => Vector3d.new(-0.18, 0, 0.5),
"CORO_MIKE" => Vector3d.new(-0.2, 0, 0.5775)
}

MARSUPIAL_PARENT_ROBOT_ROTATION_OFFSETS = {
"X1" => AngularVector3d.new(0, 0, 0),
"EXPLORER_X1" => AngularVector3d.new(0, 0, 0),
"EXPLORER_R2" => AngularVector3d.new(0, 0, -3.1416),
"CSIRO_DATA61_OZBOT_ATR" => AngularVector3d.new(0, 0, -3.1416)
"CSIRO_DATA61_OZBOT_ATR" => AngularVector3d.new(0, 0, -3.1416),
"CORO_ALLIE" => AngularVector3d.new(0, 0, 0),
"CORO_KAREN" => AngularVector3d.new(0, 0, 0),
"CORO_MIKE" => AngularVector3d.new(0, 0, 0)
}

allExecutables = ""
Expand Down