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

Setting max_velocities/accelerations for X1 and X2 #453

Merged
merged 3 commits into from
Jun 19, 2020
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
23 changes: 18 additions & 5 deletions subt_ign/launch/cave_circuit.ign
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,11 @@
end
end

$commsFadingExponent = 2.5
if $circuit == "cave"
$commsFadingExponent = 1.5
end

# spawn world offset
if $circuit == "urban"
spawnWorldXPos = 6
Expand Down Expand Up @@ -572,7 +577,7 @@

<range_config>
<max_range>500.0</max_range>
<fading_exponent>1.5</fading_exponent>
<fading_exponent><%= $commsFadingExponent %></fading_exponent>
<L0>40</L0>
<sigma>10.0</sigma>
</range_config>
Expand Down Expand Up @@ -643,6 +648,10 @@
<wheel_separation>#{0.45649 * 1.5}</wheel_separation>
<wheel_radius>0.1651</wheel_radius>
<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>
</plugin>
<!-- Publish robot state information -->
<plugin filename="libignition-gazebo-pose-publisher-system.so"
Expand Down Expand Up @@ -697,7 +706,7 @@
</sdf>
</spawn>
HEREDOC

exec = <<-HEREDOC
<executable name='x1_description'>
<command>roslaunch --wait subt_ros x1_description.launch world_name:=#{$worldName} name:=#{_name}</command>
Expand Down Expand Up @@ -753,6 +762,10 @@
<wheel_separation>#{0.33559 * 1.23}</wheel_separation>
<wheel_radius>0.098</wheel_radius>
<topic>/model/#{_name}/cmd_vel_relay</topic>
<min_velocity>-2</min_velocity>
<max_velocity>2</max_velocity>
<min_acceleration>-6</min_acceleration>
<max_acceleration>6</max_acceleration>
</plugin>
<!-- Publish robot state information -->
<plugin filename="libignition-gazebo-pose-publisher-system.so"
Expand Down Expand Up @@ -933,7 +946,7 @@
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<!--Multicopter velocity controller-->
<!--Multicopter velocity controller-->
<plugin
filename="libignition-gazebo-multicopter-control-system.so"
name="ignition::gazebo::systems::MulticopterVelocityControl">
Expand Down Expand Up @@ -1176,7 +1189,7 @@
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<!--Multicopter velocity controller-->
<!--Multicopter velocity controller-->
<plugin
filename="libignition-gazebo-multicopter-control-system.so"
name="ignition::gazebo::systems::MulticopterVelocityControl">
Expand Down Expand Up @@ -1466,7 +1479,7 @@
<is_performer>false</is_performer>
<sdf version='1.6'>
<include>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/DronePlatformX1</uri>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/DronePlatformX1</uri>
</include>
</sdf>
</spawn>
Expand Down
16 changes: 12 additions & 4 deletions subt_ign/launch/cloudsim_sim.ign
Original file line number Diff line number Diff line change
Expand Up @@ -649,6 +649,10 @@
<wheel_separation>#{0.45649 * 1.5}</wheel_separation>
<wheel_radius>0.1651</wheel_radius>
<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>
</plugin>
<!-- Publish robot state information -->
<plugin filename="libignition-gazebo-pose-publisher-system.so"
Expand Down Expand Up @@ -703,7 +707,7 @@
</sdf>
</spawn>
HEREDOC

exec = <<-HEREDOC
<executable name='x1_description'>
<command>roslaunch --wait subt_ros x1_description.launch world_name:=#{$worldName} name:=#{_name}</command>
Expand Down Expand Up @@ -759,6 +763,10 @@
<wheel_separation>#{0.33559 * 1.23}</wheel_separation>
<wheel_radius>0.098</wheel_radius>
<topic>/model/#{_name}/cmd_vel_relay</topic>
<min_velocity>-2</min_velocity>
<max_velocity>2</max_velocity>
<min_acceleration>-6</min_acceleration>
<max_acceleration>6</max_acceleration>
</plugin>
<!-- Publish robot state information -->
<plugin filename="libignition-gazebo-pose-publisher-system.so"
Expand Down Expand Up @@ -939,7 +947,7 @@
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<!--Multicopter velocity controller-->
<!--Multicopter velocity controller-->
<plugin
filename="libignition-gazebo-multicopter-control-system.so"
name="ignition::gazebo::systems::MulticopterVelocityControl">
Expand Down Expand Up @@ -1182,7 +1190,7 @@
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<!--Multicopter velocity controller-->
<!--Multicopter velocity controller-->
<plugin
filename="libignition-gazebo-multicopter-control-system.so"
name="ignition::gazebo::systems::MulticopterVelocityControl">
Expand Down Expand Up @@ -1472,7 +1480,7 @@
<is_performer>false</is_performer>
<sdf version='1.6'>
<include>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/DronePlatformX1</uri>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/DronePlatformX1</uri>
</include>
</sdf>
</spawn>
Expand Down
35 changes: 26 additions & 9 deletions subt_ign/launch/competition.ign
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,11 @@
end
end

$commsFadingExponent = 2.5
if $circuit == "cave"
$commsFadingExponent = 1.5
end

# spawn world offset
if $circuit == "urban"
spawnWorldXPos = 6
Expand Down Expand Up @@ -193,9 +198,13 @@

<%
# disable levels for simple cave worlds
levels = "true"
$levels = "true"
if $worldName.include?('simple_cave_')
levels = "false"
$levels = "false"
end

if defined?(levels) && levels != nil && !levels.empty?
$levels = levels.downcase == "true"
end
%>

Expand Down Expand Up @@ -229,7 +238,7 @@
<update_rate><%= updateRate %></update_rate>
<%end%>
<run>true</run>
<levels><%= levels %></levels>
<levels><%= $levels %></levels>
<record>
<enabled>true</enabled>
<!-- This path is used by cloudsim, please do not change -->
Expand Down Expand Up @@ -294,7 +303,7 @@
<!-- Use the <path> element to control where to record the log file.
The HOME path is used by default -->
<path>/tmp/ign/logs</path>
<filename_prefix>subt_cave</filename_prefix>
<filename_prefix>subt_<%= $circuit %></filename_prefix>
</logging>

<artifact>
Expand Down Expand Up @@ -565,7 +574,7 @@

<range_config>
<max_range>500.0</max_range>
<fading_exponent>2.5</fading_exponent>
<fading_exponent><%= $commsFadingExponent %></fading_exponent>
<L0>40</L0>
<sigma>10.0</sigma>
</range_config>
Expand Down Expand Up @@ -636,6 +645,10 @@
<wheel_separation>#{0.45649 * 1.5}</wheel_separation>
<wheel_radius>0.1651</wheel_radius>
<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>
</plugin>
<!-- Publish robot state information -->
<plugin filename="libignition-gazebo-pose-publisher-system.so"
Expand Down Expand Up @@ -690,7 +703,7 @@
</sdf>
</spawn>
HEREDOC

exec = <<-HEREDOC
<executable name='x1_description'>
<command>roslaunch --wait subt_ros x1_description.launch world_name:=#{$worldName} name:=#{_name}</command>
Expand Down Expand Up @@ -746,6 +759,10 @@
<wheel_separation>#{0.33559 * 1.23}</wheel_separation>
<wheel_radius>0.098</wheel_radius>
<topic>/model/#{_name}/cmd_vel_relay</topic>
<min_velocity>-2</min_velocity>
<max_velocity>2</max_velocity>
<min_acceleration>-6</min_acceleration>
<max_acceleration>6</max_acceleration>
</plugin>
<!-- Publish robot state information -->
<plugin filename="libignition-gazebo-pose-publisher-system.so"
Expand Down Expand Up @@ -926,7 +943,7 @@
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<!--Multicopter velocity controller-->
<!--Multicopter velocity controller-->
<plugin
filename="libignition-gazebo-multicopter-control-system.so"
name="ignition::gazebo::systems::MulticopterVelocityControl">
Expand Down Expand Up @@ -1169,7 +1186,7 @@
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<!--Multicopter velocity controller-->
<!--Multicopter velocity controller-->
<plugin
filename="libignition-gazebo-multicopter-control-system.so"
name="ignition::gazebo::systems::MulticopterVelocityControl">
Expand Down Expand Up @@ -1459,7 +1476,7 @@
<is_performer>false</is_performer>
<sdf version='1.6'>
<include>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/DronePlatformX1</uri>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/DronePlatformX1</uri>
</include>
</sdf>
</spawn>
Expand Down
37 changes: 27 additions & 10 deletions subt_ign/launch/tunnel_circuit_practice.ign
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,11 @@
end
end

$commsFadingExponent = 2.5
if $circuit == "cave"
$commsFadingExponent = 1.5
end

# spawn world offset
if $circuit == "urban"
spawnWorldXPos = 6
Expand Down Expand Up @@ -196,9 +201,13 @@

<%
# disable levels for simple cave worlds
levels = "true"
$levels = "true"
if $worldName.include?('simple_cave_')
levels = "false"
$levels = "false"
end

if defined?(levels) && levels != nil && !levels.empty?
$levels = levels.downcase == "true"
end
%>

Expand Down Expand Up @@ -232,7 +241,7 @@
<update_rate><%= updateRate %></update_rate>
<%end%>
<run>true</run>
<levels><%= levels %></levels>
<levels><%= $levels %></levels>
<record>
<enabled>true</enabled>
<!-- This path is used by cloudsim, please do not change -->
Expand Down Expand Up @@ -297,7 +306,7 @@
<!-- Use the <path> element to control where to record the log file.
The HOME path is used by default -->
<path>/tmp/ign/logs</path>
<filename_prefix>subt_tunnel_practice</filename_prefix>
<filename_prefix>subt_<%= $circuit %></filename_prefix>
</logging>

<artifact>
Expand Down Expand Up @@ -568,7 +577,7 @@

<range_config>
<max_range>500.0</max_range>
<fading_exponent>2.5</fading_exponent>
<fading_exponent><%= $commsFadingExponent %></fading_exponent>
<L0>40</L0>
<sigma>10.0</sigma>
</range_config>
Expand Down Expand Up @@ -639,6 +648,10 @@
<wheel_separation>#{0.45649 * 1.5}</wheel_separation>
<wheel_radius>0.1651</wheel_radius>
<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>
</plugin>
<!-- Publish robot state information -->
<plugin filename="libignition-gazebo-pose-publisher-system.so"
Expand All @@ -649,7 +662,7 @@
<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_publisher>true</static_publisher>
<static_update_frequency>1</static_update_frequency>
</plugin>
<!-- Battery plugin -->
Expand Down Expand Up @@ -693,7 +706,7 @@
</sdf>
</spawn>
HEREDOC

exec = <<-HEREDOC
<executable name='x1_description'>
<command>roslaunch --wait subt_ros x1_description.launch world_name:=#{$worldName} name:=#{_name}</command>
Expand Down Expand Up @@ -749,6 +762,10 @@
<wheel_separation>#{0.33559 * 1.23}</wheel_separation>
<wheel_radius>0.098</wheel_radius>
<topic>/model/#{_name}/cmd_vel_relay</topic>
<min_velocity>-2</min_velocity>
<max_velocity>2</max_velocity>
<min_acceleration>-6</min_acceleration>
<max_acceleration>6</max_acceleration>
</plugin>
<!-- Publish robot state information -->
<plugin filename="libignition-gazebo-pose-publisher-system.so"
Expand Down Expand Up @@ -929,7 +946,7 @@
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<!--Multicopter velocity controller-->
<!--Multicopter velocity controller-->
<plugin
filename="libignition-gazebo-multicopter-control-system.so"
name="ignition::gazebo::systems::MulticopterVelocityControl">
Expand Down Expand Up @@ -1172,7 +1189,7 @@
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<!--Multicopter velocity controller-->
<!--Multicopter velocity controller-->
<plugin
filename="libignition-gazebo-multicopter-control-system.so"
name="ignition::gazebo::systems::MulticopterVelocityControl">
Expand Down Expand Up @@ -1462,7 +1479,7 @@
<is_performer>false</is_performer>
<sdf version='1.6'>
<include>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/DronePlatformX1</uri>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/DronePlatformX1</uri>
</include>
</sdf>
</spawn>
Expand Down
Loading