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
@@ -1 +1 @@
nifti_robot.sdf.urdf
model.sdf.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -21,9 +21,12 @@ install(TARGETS laser_rotate_plugin flipper_control_plugin
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin)

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

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

install(PROGRAMS scripts/print_robot_urdf scripts/yaml_to_xacro_args
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/scripts)

This file was deleted.

Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
revision: 2014 # 2014 for TRADR robot, 2021 for upgraded robot

big_collision_box_on_top: False
big_collision_box_height: 0.5
big_collision_box_width: 0.5
big_collision_box_x: -0.1

flipper_inflation_ratio: 1.0
flipper_inward_enlargement: 0.0

has_flipper_touch_sensors: False
has_omnicam: True
has_omnicam_sensor_mount: True
has_omnicam_vras: False
has_sick_lidar: True
has_ouster_lidar: False
has_mote_deployer: False

num_cliff_sensors: 0

has_rear_sensor_item: True
rear_sensor_item_height: 0.35

has_top_box: True
top_box_j_x: 0.472

has_jetson: True
jetson_shift_x: 0.515
jetson_shift_y: 0.17
jetson_version: 2
jetson_yaw: 0.0

laser_pitch: 0.0

has_mobilicom: True
mobilicom_antenna_l_rotation: -0.5
mobilicom_antenna_l_tilt: 1.0
mobilicom_antenna_r_rotation: 0.0
mobilicom_antenna_r_tilt: 1.5758
mobilicom_antennas_length: 0.17
mobilicom_has_antenna_box: 0
mobilicom_is_lite: True
mobilicom_parent_link: rear_sensor_item
mobilicom_pitch: 4.0
mobilicom_roll: 1.5758
mobilicom_shift_x: 0.0
mobilicom_shift_y: 0.01
mobilicom_shift_z: 0.2
mobilicom_yaw: 3.14152

ptuxthermo_x_offset: 0.2
ptuxthermo_y_offset: 0.18

has_new_realsense: False
has_realsense: False
has_realsense_d435: True
realsense_holder_version: 5
realsense_parent_link: omnicam_sensor_mount
realsense_roll: 0.0
realsense_shift_x: 0.0
realsense_shift_y: 0.0
realsense_shift_z: 0.0
realsense_tilt: -1.15
realsense_upside_down: False
realsense_yaw: 0.62831853

has_realsense_t265: False
t265_parent_link: rear_sensor_item

This file was deleted.

Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
rendering_target: sdf

has_differential: False

realsense_width: 640
realsense_tf_from_urdf: True

simulate_sick_lidar: True
simulate_omnicam: True
simulate_imu: True
simulate_realsense_d435: True
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
scale_angular: 0.3
scale_angular_turbo: 0.5
scale_front_flippers: 1.0
scale_rear_flippers: 1.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
rendering_target: urdf

big_collision_box_on_top: True

flipper_inflation_ratio: 1.3
flipper_inward_enlargement: 0.037

mobilicom_has_antenna_box: True
Original file line number Diff line number Diff line change
@@ -0,0 +1,138 @@
def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _additionalSDF, _max_velocity=0.4, _max_acceleration=3)
numTrackWheels = 8
numFlipperWheels = 5

tracks = ["left", "right"]
flippers = ["front_left", "front_right", "rear_left", "rear_right"]

flippersOfTrack = Hash.new
flippersOfTrack["left"] = ["front_left", "rear_left"]
flippersOfTrack["right"] = ["front_right", "rear_right"]

# configuration of diffdrive
wheelSeparation = 0.397
wheelRadiuses = [0.089, 0.074, 0.059, 0.044, 0.029]

# configuration of wheel slip
slipCompliance = 0.0485
wheelNormalForce = 10.545

diffdriveJoints = []
for i in 0...numFlipperWheels
diffdriveJoints[i] = ""
end
wheelSlip = ""

for track in tracks
for wheel in 1..numTrackWheels
diffdriveJoints[0] += "<#{track}_joint>#{track}_track_wheel#{wheel}_j</#{track}_joint>\n"
wheelSlip += <<-HEREDOC
<wheel link_name="#{track}_track_wheel#{wheel}">
<slip_compliance_lateral>#{slipCompliance}</slip_compliance_lateral>
<slip_compliance_longitudinal>0</slip_compliance_longitudinal>
<wheel_normal_force>#{wheelNormalForce}</wheel_normal_force>
<wheel_radius>#{wheelRadiuses[0]}</wheel_radius>
</wheel>
HEREDOC
end
for flipper in flippersOfTrack[track]
for wheel in 1..numFlipperWheels
diffdriveJoints[wheel-1] += "<#{track}_joint>#{flipper}_flipper_wheel#{wheel}_j</#{track}_joint>\n"
wheelSlip += <<-HEREDOC
<wheel link_name="#{flipper}_flipper_wheel#{wheel}">
<slip_compliance_lateral>#{slipCompliance}</slip_compliance_lateral>
<slip_compliance_longitudinal>0</slip_compliance_longitudinal>
<wheel_normal_force>#{wheelNormalForce}</wheel_normal_force>
<wheel_radius>#{wheelRadiuses[wheel-1]}</wheel_radius>
</wheel>
HEREDOC
end
end
end

diffDrive = ""
for wheel in 0...numFlipperWheels
# we only want odometry from the first diffdrive
no_odom = ""
if wheel > 0
no_odom = "<odom_topic>unused_odom</odom_topic>\n"
end
diffDrive += <<-HEREDOC
<plugin filename="ignition-gazebo-diff-drive-system" name="ignition::gazebo::systems::DiffDrive">
#{diffdriveJoints[wheel]}
<wheel_separation>#{wheelSeparation}</wheel_separation>
<wheel_radius>#{wheelRadiuses[wheel]}</wheel_radius>
<topic>/model/#{_name}/cmd_vel_relay</topic>
<min_velocity>-#{_max_velocity}</min_velocity>
<max_velocity>#{_max_velocity}</max_velocity>
<min_acceleration>-#{_max_acceleration}</min_acceleration>
<max_acceleration>#{_max_acceleration}</max_acceleration>
#{no_odom}
</plugin>
HEREDOC
end

<<-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 -->
#{diffDrive}
<!-- 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>4.95</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="ignition-gazebo-wheel-slip-system" name="ignition::gazebo::systems::WheelSlip">
#{wheelSlip}
</plugin>
#{_additionalSDF}
</include>
</sdf>
</spawn>
HEREDOC
end

def _rosExecutables(_name, _worldName)
<<-HEREDOC
<executable name='topics'>
<command>roslaunch --wait ctu_cras_norlab_absolem_sensor_config_1 vehicle_topics.launch world_name:=#{_worldName} name:=#{_name}</command>
</executable>
HEREDOC
end
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
<?xml version="1.0"?>
<launch>
<arg name="name" doc="Name of Vehicle"/>
<param name="$(arg name)/robot_description" command="$(find xacro)/xacro '$(find ctu_cras_norlab_absolem_sensor_config_1)/urdf/nifti_robot.xacro' render_target:=urdf name:=$(arg name) big_collision_box_height:=0.5 big_collision_box_on_top:=1 big_collision_box_width:=0.5 big_collision_box_x:=-0.1 flipper_inflation_ratio:=1.3 flipper_inward_enlargement:=0.037 has_flipper_touch_sensors:=0 has_jetson:=1 has_mobilicom:=1 has_new_realsense:=0 has_omnicam:=1 has_omnicam_sensor_mount:=1 has_realsense:=0 has_realsense_d435:=1 has_realsense_t265:=0 has_rear_sensor_item:=1 has_top_box:=1 jetson_shift_x:=0.515 jetson_shift_y:=0.17 jetson_version:=2 jetson_yaw:=0.0 laser_pitch:=0.0 mobilicom_antenna_l_rotation:=-0.5 mobilicom_antenna_l_tilt:=1.0 mobilicom_antenna_r_rotation:=0.0 mobilicom_antenna_r_tilt:=1.5758 mobilicom_antennas_length:=0.17 mobilicom_has_antenna_box:=0 mobilicom_is_lite:=1 mobilicom_parent_link:=rear_sensor_item mobilicom_pitch:=4.0 mobilicom_roll:=1.5758 mobilicom_shift_x:=0.0 mobilicom_shift_y:=0.01 mobilicom_shift_z:=0.2 mobilicom_yaw:=3.14152 ptuxthermo_x_offset:=0.2 ptuxthermo_y_offset:=0.18 realsense_holder_version:=5 realsense_parent_link:=omnicam_sensor_mount realsense_roll:=0.0 realsense_shift_x:=0.0 realsense_shift_y:=0.0 realsense_shift_z:=0.0 realsense_tilt:=-1.15 realsense_upside_down:=0 realsense_yaw:=0.62831853 t265_parent_link:=rear_sensor_item top_box_j_x:=0.472"/>
<arg name="print_command" default="$(dirname)/../scripts/print_robot_urdf" />

<param name="$(arg name)/robot_description" command="$(arg print_command) name:=$(arg name)" />
</launch>

Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,8 @@

<%
#require_relative 'spawner'
load File.join(File.dirname(__FILE__), "spawner.rb")
_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
Expand All @@ -21,7 +22,7 @@
end

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

Expand All @@ -39,9 +40,17 @@

<!-- 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 %>

<% if local_variables.include?(:teleop) and teleop %>
<executable name='teleop'>
<command>roslaunch --wait ctu_cras_norlab_absolem_sensor_config_1 teleop.launch</command>
</executable>
<% end %>

<plugin name="ignition::launch::GazeboServer"
filename="libignition-launch-gazebo.so">
Expand Down Expand Up @@ -171,7 +180,10 @@
filename="libignition-launch-gazebo-factory.so">
<%= spawner(robotName, modelURI, $worldName, 0, 0, 0.2, 0, 0, 0) %>
</plugin>
<%= rosExecutables(robotName, $worldName) %>

<% if local_variables.include?(:ros) and ros %>
<%= rosExecutables(robotName, $worldName) %>
<% end %>

</ignition>

Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
<?xml version="1.0"?>
<launch>
<arg name="robot_name"/>
<arg name="joint_prefix"/>

<arg name="joint_namespace" value="/model/$(arg robot_name)/joint/$(arg joint_prefix)_flipper_j"/>

<node pkg="ros_ign_bridge" type="parameter_bridge" respawn="true"
name="ros_ign_bridge_$(arg joint_prefix)_flipper"
args="$(arg joint_namespace)/cmd_vel@std_msgs/Float64]ignition.msgs.Double">
<remap from="$(arg joint_namespace)/cmd_vel" to="flippers_cmd_vel/$(arg joint_prefix)"/>
</node>
<node pkg="ros_ign_bridge" type="parameter_bridge" respawn="true"
name="ros_ign_bridge_$(arg joint_prefix)_flipper_pos"
args="$(arg joint_namespace)/cmd_pos@std_msgs/Float64]ignition.msgs.Double">
<remap from="$(arg joint_namespace)/cmd_pos" to="flippers_cmd_pos/$(arg joint_prefix)"/>
</node>
<node pkg="ros_ign_bridge" type="parameter_bridge" respawn="true"
name="ros_ign_bridge_front_$(arg joint_prefix)_pos_rel"
args="$(arg joint_namespace)/cmd_pos_rel@std_msgs/Float64]ignition.msgs.Double">
<remap from="$(arg joint_namespace)/cmd_pos_rel" to="flippers_cmd_pos_rel/$(arg joint_prefix)"/>
</node>
<node pkg="ros_ign_bridge" type="parameter_bridge" respawn="true"
name="ros_ign_bridge_$(arg joint_prefix)_flipper_torque"
args="$(arg joint_namespace)/cmd_max_torque@std_msgs/Float64]ignition.msgs.Double">
<remap from="$(arg joint_namespace)/cmd_max_torque" to="flippers_cmd_max_torque/$(arg joint_prefix)"/>
</node>
</launch>
Loading