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
57 changes: 57 additions & 0 deletions submitted_models/coro_karen_sensor_config_1/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
cmake_minimum_required(VERSION 2.8.3)
project(coro_karen_sensor_config_1)

find_package(catkin REQUIRED COMPONENTS
roscpp
message_runtime
std_msgs
geometry_msgs
)


find_package(ignition-gazebo4 REQUIRED)
find_package(ignition-transport9 REQUIRED)
find_package(ignition-common3 REQUIRED)
find_package(Eigen3 REQUIRED)

set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)

catkin_package(
CATKIN_DEPENDS message_runtime roscpp std_msgs geometry_msgs
)


include_directories(
include
${catkin_INCLUDE_DIRS}
)

add_library(ackermannlocal SHARED
src/AckermannSteering.cc
src/SpeedLimiter.cc
)

target_link_libraries(ackermannlocal
PUBLIC ${catkin_LIBRARIES}
PRIVATE ignition-plugin1::ignition-plugin1
PRIVATE ignition-gazebo4::ignition-gazebo4
PRIVATE ignition-common3::ignition-common3
PRIVATE ignition-transport9::ignition-transport9
PRIVATE Eigen3::Eigen
)


install(TARGETS ackermannlocal
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

install(DIRECTORY launch meshes urdf worlds
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 coro_karen_sensor_config_1)/urdf/karen.xacro' name:=$(arg name)"/>
</launch>

171 changes: 171 additions & 0 deletions submitted_models/coro_karen_sensor_config_1/launch/example.ign
Original file line number Diff line number Diff line change
@@ -0,0 +1,171 @@
<?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 = 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%>

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

</ignition>
109 changes: 109 additions & 0 deletions submitted_models/coro_karen_sensor_config_1/launch/spawner.rb
Original file line number Diff line number Diff line change
@@ -0,0 +1,109 @@
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>
<!-- Ackermann Steering -->
<plugin filename="libackermannlocal.so"
name="ignition::gazebo::systems::AckermannSteering">
<left_joint>front_left_wheel_joint</left_joint>
<left_joint>rear_left_wheel_joint</left_joint>
<right_joint>front_right_wheel_joint</right_joint>
<right_joint>rear_right_wheel_joint</right_joint>
<left_steering_joint>front_left_wheel_steering_joint</left_steering_joint>
<right_steering_joint>front_right_wheel_steering_joint</right_steering_joint>
<wheel_separation>0.65</wheel_separation>
<kingpin_width>0.44</kingpin_width>
<steering_limit>0.187</steering_limit>
<wheel_base>0.93</wheel_base>
<wheel_radius>0.175</wheel_radius>
<topic>/model/#{_name}/cmd_vel_relay</topic>
<min_velocity>-1.0</min_velocity>
<max_velocity>1.0</max_velocity>
<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>
<!-- Wheel slip -->
<plugin filename="libignition-gazebo-wheel-slip-system.so"
name="ignition::gazebo::systems::WheelSlip">
<wheel link_name="front_left_wheel">
<slip_compliance_lateral>0.172</slip_compliance_lateral>
<slip_compliance_longitudinal>0.2</slip_compliance_longitudinal>
<wheel_normal_force>269.7</wheel_normal_force>
<wheel_radius>0.1275</wheel_radius>
</wheel>
<wheel link_name="rear_left_wheel">
<slip_compliance_lateral>0.172</slip_compliance_lateral>
<slip_compliance_longitudinal>0.2</slip_compliance_longitudinal>
<wheel_normal_force>269.7</wheel_normal_force>
<wheel_radius>0.1275</wheel_radius>
</wheel>
<wheel link_name="front_right_wheel">
<slip_compliance_lateral>0.172</slip_compliance_lateral>
<slip_compliance_longitudinal>0.2</slip_compliance_longitudinal>
<wheel_normal_force>269.7</wheel_normal_force>
<wheel_radius>0.1275</wheel_radius>
</wheel>
<wheel link_name="rear_right_wheel">
<slip_compliance_lateral>0.172</slip_compliance_lateral>
<slip_compliance_longitudinal>0.2</slip_compliance_longitudinal>
<wheel_normal_force>269.7</wheel_normal_force>
<wheel_radius>0.1275</wheel_radius>
</wheel>
</plugin>
</include>
</sdf>
</spawn>
HEREDOC
end

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