diff --git a/CMakeLists.txt b/CMakeLists.txt
index 951f46e..bace1a7 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -15,7 +15,10 @@ find_package(catkin REQUIRED COMPONENTS
rospy
sensor_msgs
std_msgs
+ std_srvs
tf
+ tf2
+ tf2_ros
message_generation
)
@@ -118,6 +121,8 @@ catkin_package(
sensor_msgs
std_msgs
tf
+ tf2
+ tf2_ros
message_runtime
# DEPENDS system_lib
)
diff --git a/launch/car_1.access b/launch/car_1.access
deleted file mode 100644
index c926511..0000000
--- a/launch/car_1.access
+++ /dev/null
@@ -1,25 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/car_2.access b/launch/car_2.access
deleted file mode 100644
index 7b84e56..0000000
--- a/launch/car_2.access
+++ /dev/null
@@ -1,25 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/car_3.access b/launch/car_3.access
deleted file mode 100644
index 1cac307..0000000
--- a/launch/car_3.access
+++ /dev/null
@@ -1,25 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/car_controller.launch b/launch/car_controller.launch
new file mode 100644
index 0000000..dfc87e1
--- /dev/null
+++ b/launch/car_controller.launch
@@ -0,0 +1,35 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/config/one_car.launch.xml b/launch/car_gazebo.launch
similarity index 79%
rename from config/one_car.launch.xml
rename to launch/car_gazebo.launch
index 7aacf10..605aa79 100644
--- a/config/one_car.launch.xml
+++ b/launch/car_gazebo.launch
@@ -12,6 +12,16 @@
+
+
+
+
+
+
@@ -23,13 +33,6 @@
-
-
-
@@ -54,7 +57,7 @@
-
+
diff --git a/config/vehicle_class.launch.xml b/launch/car_spawner.launch
similarity index 84%
rename from config/vehicle_class.launch.xml
rename to launch/car_spawner.launch
index 2df0dd0..0655040 100644
--- a/config/vehicle_class.launch.xml
+++ b/launch/car_spawner.launch
@@ -22,10 +22,19 @@
+
+
+
+
+
+
-
-
+
diff --git a/launch/interlagos.launch b/launch/interlagos.launch
new file mode 100644
index 0000000..fc984b2
--- /dev/null
+++ b/launch/interlagos.launch
@@ -0,0 +1,46 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/interlagos.master b/launch/interlagos.master
deleted file mode 100644
index 2200696..0000000
--- a/launch/interlagos.master
+++ /dev/null
@@ -1,43 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/monza.launch b/launch/monza.launch
new file mode 100644
index 0000000..6c95c15
--- /dev/null
+++ b/launch/monza.launch
@@ -0,0 +1,46 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/monza.master b/launch/monza.master
deleted file mode 100644
index ca2165f..0000000
--- a/launch/monza.master
+++ /dev/null
@@ -1,43 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/silverstone.launch b/launch/silverstone.launch
new file mode 100644
index 0000000..9cbedeb
--- /dev/null
+++ b/launch/silverstone.launch
@@ -0,0 +1,46 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/silverstone.master b/launch/silverstone.master
deleted file mode 100644
index fc183df..0000000
--- a/launch/silverstone.master
+++ /dev/null
@@ -1,43 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/simulator.launch b/launch/simulator.launch
new file mode 100644
index 0000000..1cf2c17
--- /dev/null
+++ b/launch/simulator.launch
@@ -0,0 +1,45 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/map/race_track.yaml b/map/race_track.yaml
index 290c46a..e8ffdc4 100644
--- a/map/race_track.yaml
+++ b/map/race_track.yaml
@@ -1,6 +1,6 @@
image: race_track.pgm
resolution: 0.050000
-origin: [-30.024998, -30.024998, 0.000000]
+origin: [-39.024998, -35.024998, 0.000000]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.196
diff --git a/package.xml b/package.xml
index 9025d2e..1e65586 100644
--- a/package.xml
+++ b/package.xml
@@ -56,6 +56,10 @@
sensor_msgs
std_msgs
tf
+ tf2
+ tf2_ros
+ std_srvs
+
message_generation
gazebo_ros
@@ -73,7 +77,10 @@
sensor_msgs
std_msgs
tf
+ tf2
+ tf2_ros
message_runtime
+ std_srvs
diff --git a/scripts/command_multiplexer.py b/scripts/command_multiplexer.py
index f51896d..e47aa1e 100755
--- a/scripts/command_multiplexer.py
+++ b/scripts/command_multiplexer.py
@@ -1,4 +1,4 @@
-#!/usr/bin/env python
+#!/usr/bin/env python3
import rospy
import sys
@@ -11,6 +11,7 @@
car_name = str(sys.argv[1])
listen_offboard = str(sys.argv[2])
+keyboard_control = str(sys.argv[3])
joy_angle_axis = 2
joy_angle_scaler = 1.0
joy_speed_axis = 1
@@ -27,11 +28,45 @@
multiplexer_pub = rospy.Publisher('/{}/multiplexer/command'.format(car_name), AckermannDrive, queue_size = 1)
offboard_command = AckermannDrive()
+rospy.set_param('/{}/command_priority'.format(car_name), control_priority[1])
+rospy.set_param('/{}/suspend_control'.format(car_name), 'False')
+
def offboard_callback(data):
global offboard_command
offboard_command.steering_angle = -1.0 * data.steering_angle
offboard_command.speed = data.speed
+def keyboard_command_callback(data):
+ global current_command_topic
+ global offboard_command
+ passthrough_command = AckermannDrive()
+ # listen to control transfer commands
+ if rospy.get_param('/{}/command_priority'.format(car_name)) == control_priority[0]:
+ if not message_display[0]:
+ rospy.loginfo(log_message.format(control_priority[0]))
+ message_display[0] = True
+ message_display[1] = False
+ if current_command_topic != command_topic[0]:
+ current_command_topic = command_topic[0]
+ if rospy.get_param('/{}/command_priority'.format(car_name)) == control_priority[1]:
+ if not message_display[1]:
+ rospy.loginfo(log_message.format(control_priority[1]))
+ message_display[0] = False
+ message_display[1] = True
+ if current_command_topic != command_topic[1]:
+ current_command_topic = command_topic[1]
+ if current_command_topic == command_topic[1]:
+ # identify and scale raw command data
+ passthrough_command = data
+ elif current_command_topic == command_topic[0] and listen_offboard == 'true':
+ passthrough_command = offboard_command
+ if rospy.get_param('/{}/suspend_control'.format(car_name)) in ['True', 'true', '1', '1.0']:
+ passthrough_command.steering_angle = 0.0
+ passthrough_command.speed = 0.0
+ multiplexer_pub.publish(passthrough_command)
+ else:
+ multiplexer_pub.publish(passthrough_command)
+
def joy_command_callback(data):
global current_command_topic
global offboard_command
@@ -64,7 +99,10 @@ def joy_command_callback(data):
rospy.init_node('command_multiplexer', anonymous = True)
if listen_offboard == 'true':
rospy.Subscriber('/{}/offboard/command'.format(car_name), AckermannDrive, offboard_callback)
- rospy.Subscriber('/{}/joy'.format(car_name), Joy, joy_command_callback)
+ if keyboard_control == 'true':
+ rospy.Subscriber('/{}/teleop/command'.format(car_name), AckermannDrive, keyboard_command_callback)
+ else:
+ rospy.Subscriber('/{}/teleop/command'.format(car_name), Joy, joy_command_callback)
rospy.spin()
except rospy.ROSInterruptException:
pass
diff --git a/scripts/keyboard_teleop.py b/scripts/keyboard_teleop.py
index 6402d6e..c71d83e 100755
--- a/scripts/keyboard_teleop.py
+++ b/scripts/keyboard_teleop.py
@@ -1,4 +1,4 @@
-#!/usr/bin/env python
+#!/usr/bin/env python3
import rospy
import sys
@@ -14,7 +14,7 @@
's':(-1.0, 0.0), # move reverse
'q':(0.0, 0.0)} # all stop
-speed_limit = 0.250
+speed_limit = 1.25
angle_limit = 0.325
def getKey():
diff --git a/src/control_plugin.py b/src/control_plugin.py
index c3db9e1..78b1abb 100755
--- a/src/control_plugin.py
+++ b/src/control_plugin.py
@@ -1,8 +1,9 @@
-#!/usr/bin/env python
+#!/usr/bin/env python3
import rospy
import math
import sys
+import ast
import tf2_ros
from std_msgs.msg import Header
@@ -18,8 +19,6 @@
# vehicle name
car_name = str(sys.argv[1])
-x_offset = float(sys.argv[2])
-y_offset = float(sys.argv[3])
# subscriber topics
@@ -42,9 +41,14 @@
# frame names
-odom_frame = 'odom'
+odom_frame = '{}_odom'.format(car_name)
base_frame = '{}_base_link'.format(car_name)
+# Get car init pose as offset
+init_pose = Point32()
+init_pose_param = ast.literal_eval(rospy.get_param('/{}/init_pose'.format(car_name)))
+init_pose.x, init_pose.y, init_pose.z = init_pose_param
+
# information publishers
footprint_pub = rospy.Publisher(footprint_topic, PolygonStamped, queue_size = 1)
@@ -100,8 +104,8 @@ def odom_callback(data):
odom.child_frame_id = base_frame
odom.header.stamp = rospy.Time.now()
odom.pose = data.pose
- odom.pose.pose.position.x = odom.pose.pose.position.x - x_offset
- odom.pose.pose.position.y = odom.pose.pose.position.y - y_offset
+ odom.pose.pose.position.x = odom.pose.pose.position.x - init_pose.x
+ odom.pose.pose.position.y = odom.pose.pose.position.y - init_pose.y
odom.twist = data.twist
tf = TransformStamped(header = Header(
@@ -113,7 +117,6 @@ def odom_callback(data):
rotation = odom.pose.pose.orientation))
# visualize footprint everytime odom changes
-
footprint_visualizer()
odom_pub.publish(odom)
@@ -128,6 +131,7 @@ def odom_callback(data):
max_speed = 80.0 # 100.0
speed_delta = 5.0 # 1.25
previous_speed = 0.0
+wheelRaidus = 0.05 # from wheel collision property
# command callback
@@ -138,8 +142,10 @@ def command_callback(data):
steering_angle = Float64()
speed = Float64()
- steering_angle.data = data.steering_angle * 0.65
- speed.data = data.speed * max_speed
+ steering_angle.data = data.steering_angle
+
+ # convert local frame (m/s) to joint speed (radian/s)
+ speed.data = data.speed / wheelRaidus
'''
if speed.data >= previous_speed + speed_delta:
diff --git a/src/set_racecar_state.py b/src/set_racecar_state.py
index 6009195..d2d5e9b 100755
--- a/src/set_racecar_state.py
+++ b/src/set_racecar_state.py
@@ -1,15 +1,24 @@
-#!/usr/bin/env python
+#!/usr/bin/env python3
import rospy
import rospkg
import sys
+import ast
from gazebo_msgs.msg import ModelState
from gazebo_msgs.srv import SetModelState
+from geometry_msgs.msg import Point
+from std_srvs.srv import Empty
car_name = str(sys.argv[1])
acceptable_reset = ['true', 'True', '1', '1.0']
loop_quit = False
+
+# Get car init pose as offset
+init_pose = Point()
+init_pose_param = ast.literal_eval(rospy.get_param('/{}/init_pose'.format(car_name)))
+init_pose.x, init_pose.y, init_pose.z = init_pose_param
+
# x_pos = float(sys.argv[2])
# y_pos = float(sys.argv[3])
# z_pos = float(sys.argv[4])
@@ -28,32 +37,32 @@
rospy.set_param('/{}/reset_to_pit_stop'.format(car_name), 'False')
-def racecar_reset_state():
- rospy.init_node('racecar_reset_pit_stop', anonymous = True)
-
+def racecar_reset_state(req):
+
state_msg = ModelState()
state_msg.model_name = car_name
- exec('state_msg.pose.position.x = {}_reset_pose[0]'.format(car_name))
- exec('state_msg.pose.position.y = {}_reset_pose[1]'.format(car_name))
- exec('state_msg.pose.position.z = {}_reset_pose[2]'.format(car_name))
+ state_msg.pose.position = init_pose
state_msg.pose.orientation.x = 0.0
state_msg.pose.orientation.y = 0.0
state_msg.pose.orientation.z = 0.0
- state_msg.pose.orientation.w = 0.0
+ state_msg.pose.orientation.w = 1.0
rospy.wait_for_service('/gazebo/set_model_state')
try:
set_state = rospy.ServiceProxy('/gazebo/set_model_state', SetModelState)
resp = set_state(state_msg)
- except rospy.ServiceException, error_msg:
+ except rospy.ServiceException as error_msg:
print("Service call failed: %s" % error_msg)
+ return True
+
if __name__ == '__main__':
try:
- while not loop_quit:
- if str(rospy.get_param('/{}/reset_to_pit_stop'.format(car_name))) in acceptable_reset:
- racecar_reset_state()
- rospy.set_param('/{}/reset_to_pit_stop'.format(car_name), 'False')
+ rospy.init_node('racecar_reset_pit_stop', anonymous = True)
+ reset_srv = rospy.Service('/{}/reset_to_pit_stop'.format(car_name), Empty, racecar_reset_state)
+
+ rospy.spin()
+
except rospy.ROSInterruptException:
pass
diff --git a/urdf/macros.xacro b/urdf/macros.xacro
index 47b2755..96cfbf5 100644
--- a/urdf/macros.xacro
+++ b/urdf/macros.xacro
@@ -152,6 +152,9 @@
+
+
+
@@ -182,7 +185,7 @@
- robot
+
@@ -323,13 +326,13 @@
-
+
-
+
@@ -338,7 +341,7 @@
-
+
@@ -474,12 +477,12 @@
-
+
Gazebo/Grey
- 0 0 0.0124 0 0 0
+ 0 0 0 0 0 0
false
40
diff --git a/world/models/race_track/model.config b/world/models/race_track/model.config
new file mode 100644
index 0000000..6e86f8a
--- /dev/null
+++ b/world/models/race_track/model.config
@@ -0,0 +1,13 @@
+
+
+
+
+ race_track
+ 1.0
+ model.sdf
+
+ Varundev Suresh Babu
+ varundev@virginia.edu
+
+
+
diff --git a/world/models/race_track/model.sdf b/world/models/race_track/model.sdf
new file mode 100644
index 0000000..c9a2a7e
--- /dev/null
+++ b/world/models/race_track/model.sdf
@@ -0,0 +1,31 @@
+
+
+
+
+
+
+
+
+
+
+
+ model://f1tenth-sim/world/race_track/race_track.stl
+
+
+
+
+
+
+
+ model://f1tenth-sim/world/race_track/race_track.stl
+
+
+
+
+
+
+ 1
+
+
+
+
diff --git a/world/models/race_track/race_track.stl b/world/models/race_track/race_track.stl
new file mode 100644
index 0000000..a48f2ed
Binary files /dev/null and b/world/models/race_track/race_track.stl differ
diff --git a/world/race_track.world b/world/race_track.world
new file mode 100644
index 0000000..9345795
--- /dev/null
+++ b/world/race_track.world
@@ -0,0 +1,218 @@
+
+
+
+ 1
+ 0 0 100 0 -0 0
+ 0.8 0.8 0.8 1
+ 0.1 0.1 0.1 1
+
+ 1000
+ 0.9
+ 0.01
+ 0.001
+
+ -0.5 0.5 -1
+
+
+ 1
+
+
+
+
+ 0 0 1
+ 100 100
+
+
+
+
+
+ 100
+ 50
+
+
+
+
+
+
+
+
+
+
+ 10
+
+
+ 0
+
+
+ 0 0 1
+ 100 100
+
+
+
+
+
+
+ 0
+ 0
+ 1
+ 0
+
+
+ 0 0 -9.8
+ 6e-06 2.3e-05 -4.2e-05
+
+
+ 0.001
+ 1
+ 1000
+
+
+ 0.4 0.4 0.4 1
+ 0.7 0.7 0.7 1
+ 1
+
+
+ EARTH_WGS84
+ 0
+ 0
+ 0
+ 0
+
+
+ 1
+
+
+
+
+ 28.54 22.04 0.1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 0
+
+
+ 28.54 22.04 0.1
+
+
+
+
+
+
+ 0
+ 0
+ 1
+ 0
+
+ -0.719505 0.551979 0 0 -0 0
+
+
+ -39.47 -22.7 0 0 -0 0
+ 1
+
+
+
+
+ model://race_track/race_track.stl
+ 0.1 0.1 0.1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ model://race_track/race_track.stl
+ 0.1 0.1 0.025
+
+
+
+ 0
+ 0
+ 0
+
+
+
+
+
+ 170 535000000
+ 72 357007893
+ 1584808949 743558627
+ 72173
+
+ -0.719505 0.551979 0 0 -0 0
+ 1 1 1
+
+ -0.719505 0.551979 0 0 -0 0
+ 0 0 0 0 -0 0
+ 0 0 0 0 -0 0
+ 0 0 0 0 -0 0
+
+
+
+ 0 0 0 0 -0 0
+ 1 1 1
+
+ 0 0 0 0 -0 0
+ 0 0 0 0 -0 0
+ 0 0 0 0 -0 0
+ 0 0 0 0 -0 0
+
+
+
+ -28.0315 -24.6199 0 0 -0 0
+ 1 1 1
+
+ -28.0315 -24.6199 0 0 -0 0
+ 0 0 0 0 -0 0
+ 0 0 0 0 -0 0
+ 0 0 0 0 -0 0
+
+
+
+ 0 0 100 0 -0 0
+
+
+
+
+ -25.5315 -42.4719 35.3512 -0 0.687642 1.15301
+ orbit
+ perspective
+
+
+
+
diff --git a/world/race_track_obstacles.world b/world/race_track_obstacles.world
new file mode 100644
index 0000000..8d750a3
--- /dev/null
+++ b/world/race_track_obstacles.world
@@ -0,0 +1,1458 @@
+
+
+
+ 1
+ 0 0 100 0 -0 0
+ 0.8 0.8 0.8 1
+ 0.1 0.1 0.1 1
+
+ 1000
+ 0.9
+ 0.01
+ 0.001
+
+ -0.5 0.5 -1
+
+
+ 1
+
+
+
+
+ 0 0 1
+ 100 100
+
+
+
+
+
+ 100
+ 50
+
+
+
+
+
+
+
+
+
+
+ 10
+
+
+ 0
+
+
+ 0 0 1
+ 100 100
+
+
+
+
+
+
+ 0
+ 0
+ 1
+ 0
+
+
+ 0 0 -9.8
+ 6e-06 2.3e-05 -4.2e-05
+
+
+ 0.001
+ 1
+ 1000
+
+
+ 0.4 0.4 0.4 1
+ 0.7 0.7 0.7 1
+ 1
+
+
+ EARTH_WGS84
+ 0
+ 0
+ 0
+ 0
+
+
+ 1
+
+
+
+
+ 28.54 22.04 0.1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 0
+
+
+ 28.54 22.04 0.1
+
+
+
+
+
+
+ 0
+ 0
+ 1
+ 0
+
+ -0.719505 0.551979 0 0 -0 0
+
+
+ -39.47 -22.7 0 0 -0 0
+ 1
+
+
+
+
+ model://race_track/race_track.stl
+ 0.1 0.1 0.1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ model://race_track/race_track.stl
+ 0.1 0.1 0.025
+
+
+
+ 0
+ 0
+ 0
+
+
+
+
+
+ 373 464000000
+ 204 92896969
+ 1587932966 740711163
+ 202929
+
+ -0.719505 0.551979 0 0 -0 0
+ 1 1 1
+
+ -0.719505 0.551979 0 0 -0 0
+ 0 0 0 0 -0 0
+ 0 0 0 0 -0 0
+ 0 0 0 0 -0 0
+
+
+
+ 0 0 0 0 -0 0
+ 1 1 1
+
+ 0 0 0 0 -0 0
+ 0 0 0 0 -0 0
+ 0 0 0 0 -0 0
+ 0 0 0 0 -0 0
+
+
+
+ -28.0315 -24.6199 0 0 -0 0
+ 1 1 1
+
+ -28.0315 -24.6199 0 0 -0 0
+ 0 0 0 0 -0 0
+ 0 0 0 0 -0 0
+ 0 0 0 0 -0 0
+
+
+
+ -9.27266 -7.142 0.55 -0 -0 -0
+ 1 1 1
+
+ -9.27266 -7.142 0.55 -0 -0 -0
+ 0 0 0 0 -0 0
+ -0 -0 0 0 -0 0
+ -0 -0 0 0 -0 0
+
+
+
+ -2.81388 -8.82208 0.550002 -4e-06 -0 1.2e-05
+ 1 1 1
+
+ -2.81388 -8.82208 0.550002 -4e-06 -0 1.2e-05
+ 0 0 0 0 -0 0
+ 0.007945 -5.48599 -0.656764 -1.59478 0.01491 -0.002379
+ 0.007945 -5.48599 -0.656764 0 -0 0
+
+
+
+ 3.59666 -5.7101 0.55 0 -0 1.1e-05
+ 1 1 1
+
+ 3.59666 -5.7101 0.55 0 -0 1.1e-05
+ 0 0 0 0 -0 0
+ -4.03273 0.968671 5.01025 1.20431 -1.35803 -3.14084
+ -4.03273 0.968671 5.01025 0 -0 0
+
+
+
+ 11.4527 -7.49622 0.550002 -4e-06 -0 1.1e-05
+ 1 1 1
+
+ 11.4527 -7.49622 0.550002 -4e-06 -0 1.1e-05
+ 0 0 0 0 -0 0
+ 0.007938 -5.48599 -0.656764 -1.59478 0.014897 -0.002379
+ 0.007938 -5.48599 -0.656764 0 -0 0
+
+
+
+ 3.37425 8.03638 0.55 0 -0 5e-06
+ 1 1 1
+
+ 3.37425 8.03638 0.55 0 -0 5e-06
+ 0 0 0 0 -0 0
+ -4.03273 0.968696 5.01026 1.20426 -1.35804 -3.14084
+ -4.03273 0.968696 5.01026 0 -0 0
+
+
+
+ -2.28609 7.73137 0.550002 -4e-06 -0 4e-06
+ 1 1 1
+
+ -2.28609 7.73137 0.550002 -4e-06 -0 4e-06
+ 0 0 0 0 -0 0
+ 0.007904 -5.48599 -0.656765 -1.59478 0.014828 -0.00238
+ 0.007904 -5.48599 -0.656765 0 -0 0
+
+
+
+ -5.89619 10.1646 0.55 0 -0 4e-06
+ 1 1 1
+
+ -5.89619 10.1646 0.55 0 -0 4e-06
+ 0 0 0 0 -0 0
+ -4.03272 0.968701 5.01026 1.20425 -1.35804 -3.14084
+ -4.03272 0.968701 5.01026 0 -0 0
+
+
+
+ -10.1615 7.04332 0.550002 -4e-06 -0 3e-06
+ 1 1 1
+
+ -10.1615 7.04332 0.550002 -4e-06 -0 3e-06
+ 0 0 0 0 -0 0
+ 0.007897 -5.48599 -0.656765 -1.59478 0.014814 -0.00238
+ 0.007897 -5.48599 -0.656765 0 -0 0
+
+
+
+ -13.8632 3.44477 0.55 0 -0 3e-06
+ 1 1 1
+
+ -13.8632 3.44477 0.55 0 -0 3e-06
+ 0 0 0 0 -0 0
+ -4.03272 0.968706 5.01026 1.20423 -1.35804 -3.14084
+ -4.03272 0.968706 5.01026 0 -0 0
+
+
+
+ -13.1878 10.0939 0.550002 -4e-06 -0 2e-06
+ 1 1 1
+
+ -13.1878 10.0939 0.550002 -4e-06 -0 2e-06
+ 0 0 0 0 -0 0
+ 0.007891 -5.48599 -0.656765 -1.59478 0.014801 -0.00238
+ 0.007891 -5.48599 -0.656765 0 -0 0
+
+
+
+ -11.057 -1.13421 0.55 0 -0 1e-06
+ 1 1 1
+
+ -11.057 -1.13421 0.55 0 -0 1e-06
+ 0 0 0 0 -0 0
+ -4.03272 0.968711 5.01026 1.20423 -1.35804 -3.14084
+ -4.03272 0.968711 5.01026 0 -0 0
+
+
+
+ -13.6269 -5.4654 0.55 0 -0 1e-06
+ 1 1 1
+
+ -13.6269 -5.4654 0.55 0 -0 1e-06
+ 0 0 0 0 -0 0
+ 0.043246 -5.62162 5.61985 -1.32422 0.073966 -0.009168
+ 0.043246 -5.62162 5.61985 0 -0 0
+
+
+
+ 10.1713 2.31269 0.55 0 -0 1e-05
+ 1 1 1
+
+ 10.1713 2.31269 0.55 0 -0 1e-05
+ 0 0 0 0 -0 0
+ -4.03273 0.968676 5.01026 1.2043 -1.35803 -3.14084
+ -4.03273 0.968676 5.01026 0 -0 0
+
+
+
+ 12.2587 6.74361 0.550002 -4e-06 -0 1e-05
+ 1 1 1
+
+ 12.2587 6.74361 0.550002 -4e-06 -0 1e-05
+ 0 0 0 0 -0 0
+ 0.007932 -5.48599 -0.656764 -1.59478 0.014883 -0.002379
+ 0.007932 -5.48599 -0.656764 0 -0 0
+
+
+
+ 6.04497 8.55611 0.55 0 -0 9e-06
+ 1 1 1
+
+ 6.04497 8.55611 0.55 0 -0 9e-06
+ 0 0 0 0 -0 0
+ -4.03273 0.968681 5.01026 1.20429 -1.35803 -3.14084
+ -4.03273 0.968681 5.01026 0 -0 0
+
+
+
+ 2.54349 -0.635871 0.550002 -4e-06 -0 8e-06
+ 1 1 1
+
+ 2.54349 -0.635871 0.550002 -4e-06 -0 8e-06
+ 0 0 0 0 -0 0
+ 0.007925 -5.48599 -0.656764 -1.59478 0.014869 -0.002379
+ 0.007925 -5.48599 -0.656764 0 -0 0
+
+
+
+ -3.63642 -1.17096 0.55 0 -0 8e-06
+ 1 1 1
+
+ -3.63642 -1.17096 0.55 0 -0 8e-06
+ 0 0 0 0 -0 0
+ -4.03273 0.968686 5.01026 1.20427 -1.35803 -3.14084
+ -4.03273 0.968686 5.01026 0 -0 0
+
+
+
+ -6.71225 1.78806 0.550002 -4e-06 0 7e-06
+ 1 1 1
+
+ -6.71225 1.78806 0.550002 -4e-06 0 7e-06
+ 0 0 0 0 -0 0
+ 0.007918 -5.48599 -0.656764 -1.59478 0.014856 -0.002379
+ 0.007918 -5.48599 -0.656764 0 -0 0
+
+
+
+ -8.3775 5.49633 0.55 0 -0 6e-06
+ 1 1 1
+
+ -8.3775 5.49633 0.55 0 -0 6e-06
+ 0 0 0 0 -0 0
+ -4.03273 0.968691 5.01026 1.20426 -1.35804 -3.14084
+ -4.03273 0.968691 5.01026 0 -0 0
+
+
+
+ -1.19864 3.40043 0.550002 -4e-06 -0 6e-06
+ 1 1 1
+
+ -1.19864 3.40043 0.550002 -4e-06 -0 6e-06
+ 0 0 0 0 -0 0
+ 0.007911 -5.48599 -0.656765 -1.59478 0.014842 -0.002379
+ 0.007911 -5.48599 -0.656765 0 -0 0
+
+
+
+ 0 0 100 0 -0 0
+
+
+
+
+ -1.99521 -32.9632 24.4789 0 0.695639 1.52182
+ orbit
+ perspective
+
+
+
+ -9.27266 -7.142 0.5 0 -0 0
+
+
+ 1
+
+ 0.166667
+ 0
+ 0
+ 0.166667
+ 0
+ 0.166667
+
+
+
+
+
+ 1 1 1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+ -2.81387 -8.82208 0.55 -0 -0 -0
+
+
+ 1
+
+ 0.166667
+ 0
+ 0
+ 0.166667
+ 0
+ 0.166667
+
+
+
+
+
+ 1 1 1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+ 3.59667 -5.7101 0.55 -0 -0 -0
+
+
+ 1
+
+ 0.166667
+ 0
+ 0
+ 0.166667
+ 0
+ 0.166667
+
+
+
+
+
+ 1 1 1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+ 11.4527 -7.49622 0.55 -0 -0 -0
+
+
+ 1
+
+ 0.166667
+ 0
+ 0
+ 0.166667
+ 0
+ 0.166667
+
+
+
+
+
+ 1 1 1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+ 10.1713 2.31269 0.55 -0 -0 -0
+
+
+ 1
+
+ 0.166667
+ 0
+ 0
+ 0.166667
+ 0
+ 0.166667
+
+
+
+
+
+ 1 1 1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+ 12.2587 6.74361 0.55 -0 -0 -0
+
+
+ 1
+
+ 0.166667
+ 0
+ 0
+ 0.166667
+ 0
+ 0.166667
+
+
+
+
+
+ 1 1 1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+ 6.04498 8.55611 0.55 -0 -0 -0
+
+
+ 1
+
+ 0.166667
+ 0
+ 0
+ 0.166667
+ 0
+ 0.166667
+
+
+
+
+
+ 1 1 1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+ 2.5435 -0.635874 0.55 -0 -0 -0
+
+
+ 1
+
+ 0.166667
+ 0
+ 0
+ 0.166667
+ 0
+ 0.166667
+
+
+
+
+
+ 1 1 1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+ -3.63641 -1.17096 0.55 -0 -0 -0
+
+
+ 1
+
+ 0.166667
+ 0
+ 0
+ 0.166667
+ 0
+ 0.166667
+
+
+
+
+
+ 1 1 1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+ -6.71224 1.78806 0.55 -0 -0 -0
+
+
+ 1
+
+ 0.166667
+ 0
+ 0
+ 0.166667
+ 0
+ 0.166667
+
+
+
+
+
+ 1 1 1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+ -8.37749 5.49633 0.55 -0 -0 -0
+
+
+ 1
+
+ 0.166667
+ 0
+ 0
+ 0.166667
+ 0
+ 0.166667
+
+
+
+
+
+ 1 1 1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+ -1.19863 3.40043 0.55 -0 -0 -0
+
+
+ 1
+
+ 0.166667
+ 0
+ 0
+ 0.166667
+ 0
+ 0.166667
+
+
+
+
+
+ 1 1 1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+ 3.37425 8.03638 0.55 -0 -0 -0
+
+
+ 1
+
+ 0.166667
+ 0
+ 0
+ 0.166667
+ 0
+ 0.166667
+
+
+
+
+
+ 1 1 1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+ -2.28609 7.73137 0.55 -0 -0 -0
+
+
+ 1
+
+ 0.166667
+ 0
+ 0
+ 0.166667
+ 0
+ 0.166667
+
+
+
+
+
+ 1 1 1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+ -5.89619 10.1646 0.55 -0 -0 -0
+
+
+ 1
+
+ 0.166667
+ 0
+ 0
+ 0.166667
+ 0
+ 0.166667
+
+
+
+
+
+ 1 1 1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+ -10.1615 7.04332 0.55 -0 -0 -0
+
+
+ 1
+
+ 0.166667
+ 0
+ 0
+ 0.166667
+ 0
+ 0.166667
+
+
+
+
+
+ 1 1 1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+ -13.8632 3.44477 0.55 -0 -0 -0
+
+
+ 1
+
+ 0.166667
+ 0
+ 0
+ 0.166667
+ 0
+ 0.166667
+
+
+
+
+
+ 1 1 1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+ -13.1878 10.0939 0.55 -0 -0 -0
+
+
+ 1
+
+ 0.166667
+ 0
+ 0
+ 0.166667
+ 0
+ 0.166667
+
+
+
+
+
+ 1 1 1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+ -11.057 -1.13421 0.55 -0 -0 -0
+
+
+ 1
+
+ 0.166667
+ 0
+ 0
+ 0.166667
+ 0
+ 0.166667
+
+
+
+
+
+ 1 1 1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+ -13.6269 -5.4654 0.55 -0 -0 -0
+
+
+ 1
+
+ 0.166667
+ 0
+ 0
+ 0.166667
+ 0
+ 0.166667
+
+
+
+
+
+ 1 1 1
+
+
+ 10
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+