export_to_svg.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 """
4 ========================================================================================
5 # This small script subscribes to the FeedbackMsg message of teb_local_planner
6 # and converts the current scene to a svg-image
7 # publish_feedback must be turned on such that the planner publishes this information.
8 # Author: christoph.roesmann@tu-dortmund.de
9 
10 It is recommendable to start this node after initialization of TEB is completed.
11 
12 Requirements:
13 svgwrite: A Python library to create SVG drawings. http://pypi.python.org/pypi/svgwrite
14 =======================================================================================
15 """
16 import roslib;
17 import rospy
18 import svgwrite
19 import math
20 import sys
21 import time
22 import random
23 from svgwrite import cm, mm
24 from teb_local_planner.msg import FeedbackMsg, TrajectoryMsg, TrajectoryPointMsg
25 from geometry_msgs.msg import PolygonStamped, Point32, Quaternion
26 
27 
28 # ================= PARAMETERS ==================
29 # TODO: In case of a more general node, change parameter to ros-parameter
30 # Drawing parameters:
31 SCALE = 200 # Overall scaling: 100 pixel = 1 m
32 MIN_POSE_DISTANCE = 0.3 # Distance between two consecutive poses in SVG-image
33 SCALE_VELOCITY_VEC = 0.4 # Scaling of velocity vectors -> 1 cell = 1/SCALE_VELOCITY_VEC m/s
34 GRID_X_MIN = -2 # Define, how many cells your grid should contain in each direction.
35 GRID_X_MAX = 2
36 GRID_Y_MIN = -2
37 GRID_Y_MAX = 1
38 
39 # TEB parameters:
40 OBSTACLE_DIST = 50 *SCALE/100 # cm
41 
42 
43 # ================= FUNCTIONS ===================
44 
45 def sign(number):
46  """
47  Signum function: get sign of a number
48 
49  @param number: get sign of this number
50  @type number: numeric type (eg. integer)
51  @return: sign of number
52  @rtype: integer {1, -1, 0}
53  """
54  return cmp(number,0)
55 
56 def arrowMarker(color='green', orientation='auto'):
57  """
58  Create an arrow marker with svgwrite
59 
60  @return: arrow marker
61  @rtype: svg_write marker object
62  """
63  arrow = svg.marker(insert=(1,5), size=(4,3), orient=orientation)
64  arrow.viewbox(width=10, height=10)
65  arrow.add(svg.polyline([(0,0),(10,5),(0,10),(1,5)], fill=color, opacity=1.0))
66  svg.defs.add(arrow)
67  return arrow
68 
69 def quaternion2YawDegree(orientation):
70  """
71  Get yaw angle [degree] from quaternion representation
72 
73  @param orientation: orientation in quaternions to read from
74  @type orientation: geometry_msgs/Quaternion
75  @return: yaw angle [degree]
76  @rtype: float
77  """
78  yawRad = math.atan2(2*(orientation.x*orientation.y+orientation.z*orientation.w),1-2*(pow(orientation.y,2)+pow(orientation.z,2)))
79  return yawRad*180/math.pi
80 
81 
83  """
84  Callback for receiving TEB and obstacle information
85 
86  @param data: Received feedback message
87  @type data: visualization_msgs/Marker
88 
89  @globalparam tebList: Received TEB List
90  @globaltype tebList: teb_local_planner/FeedbackMsg
91  """
92  # TODO: Remove global variables
93  global feedbackMsg
94 
95  if not feedbackMsg:
96  feedbackMsg = data
97  rospy.loginfo("TEB feedback message received...")
98 
99 
100 # ================ MAIN FUNCTION ================
101 
102 if __name__ == '__main__':
103  rospy.init_node('export_to_svg', anonymous=True)
104 
105  topic_name = "/test_optim_node/teb_feedback" # define feedback topic here!
106 
107  rospy.Subscriber(topic_name, FeedbackMsg, feedback_callback, queue_size = 1)
108 
109  rospy.loginfo("Waiting for feedback message on topic %s.", topic_name)
110 
111  rate = rospy.Rate(10.0)
112  feedbackMsg = []
113 
114  timestr = time.strftime("%Y%m%d_%H%M%S")
115  filename_string = "teb_svg_" + timestr + '.svg'
116 
117  rospy.loginfo("SVG will be written to '%s'.", filename_string)
118 
119  random.seed(0)
120 
121  svg=svgwrite.Drawing(filename=filename_string, debug=True)
122 
123  # Create viewbox -> this box defines the size of the visible drawing
124  svg.viewbox(GRID_X_MIN*SCALE-1*SCALE,GRID_Y_MIN*SCALE-1*SCALE,GRID_X_MAX*SCALE-GRID_X_MIN*SCALE+2*SCALE,GRID_Y_MAX*SCALE-GRID_Y_MIN*SCALE+2*SCALE)
125 
126  # Draw grid:
127  hLines = svg.add(svg.g(id='hLines', stroke='black'))
128  hLines.add(svg.line(start=(GRID_X_MIN*SCALE, 0), end=(GRID_X_MAX*SCALE, 0)))
129  for y in range(GRID_Y_MAX):
130  hLines.add(svg.line(start=(GRID_X_MIN*SCALE, SCALE+y*SCALE), end=(GRID_X_MAX*SCALE, SCALE+y*SCALE)))
131  for y in range(-GRID_Y_MIN):
132  hLines.add(svg.line(start=(GRID_X_MIN*SCALE, -SCALE-y*SCALE), end=(GRID_X_MAX*SCALE, -SCALE-y*SCALE)))
133  vLines = svg.add(svg.g(id='vline', stroke='black'))
134  vLines.add(svg.line(start=(0, GRID_Y_MIN*SCALE), end=(0, GRID_Y_MAX*SCALE)))
135  for x in range(GRID_X_MAX):
136  vLines.add(svg.line(start=(SCALE+x*SCALE, GRID_Y_MIN*SCALE), end=(SCALE+x*SCALE, GRID_Y_MAX*SCALE)))
137  for x in range(-GRID_X_MIN):
138  vLines.add(svg.line(start=(-SCALE-x*SCALE, GRID_Y_MIN*SCALE), end=(-SCALE-x*SCALE, GRID_Y_MAX*SCALE)))
139 
140 
141  # Draw legend:
142  legend = svg.g(id='legend', font_size=25)
143  stringGeometry = "Geometry: 1 Unit = 1.0m"
144  legendGeometry = svg.text(stringGeometry)
145  legend.add(legendGeometry)
146  legend.translate(tx=GRID_X_MIN*SCALE, ty=GRID_Y_MAX*SCALE + 30) # Move legend to buttom left corner
147  svg.add(legend)
148 
149 
150  #arrow = arrowMarker() # Init arrow marker
151 
152  rospy.loginfo("Initialization completed.\nWaiting for feedback message...")
153 
154  # -------------------- WAIT FOR CALLBACKS --------------------------
155  while not rospy.is_shutdown():
156  if feedbackMsg:
157  break # Leave loop after receiving all necessary TEB information (see callbacks) to finish drawing
158  rate.sleep()
159  # ------------------------------------------------------------------
160 
161  if not feedbackMsg.trajectories:
162  rospy.loginfo("Received message does not contain trajectories. Shutting down...")
163  sys.exit()
164 
165  if len(feedbackMsg.trajectories[0].trajectory) < 2:
166  rospy.loginfo("Received message does not contain trajectories with at least two states (start and goal). Shutting down...")
167  sys.exit()
168 
169  # iterate trajectories
170  for index, traj in enumerate(feedbackMsg.trajectories):
171 
172  #color
173  traj_color = svgwrite.rgb(random.randint(0, 255), random.randint(0, 255), random.randint(0, 255), 'RGB')
174 
175  # Iterate through TEB positions -> Draw Paths
176  points = []
177  for point in traj.trajectory:
178  points.append( (point.pose.position.x*SCALE,-point.pose.position.y*SCALE) ) # y is negative in image coordinates
179  # svgwrite rotates clockwise!
180 
181 
182  if index == feedbackMsg.selected_trajectory_idx: # highlight currently selected teb
183  line = svg.add( svg.polyline(points=points, fill='none', stroke=traj_color, stroke_width=10, stroke_linecap='round', \
184  stroke_linejoin='round', opacity=1.0 ) )
185  else:
186  line = svg.add( svg.polyline(points=points, fill='none', stroke=traj_color, stroke_width=10, stroke_linecap='butt', \
187  stroke_linejoin='round', stroke_dasharray='10,3', opacity=1.0 ) )
188  #marker_points = points[::7]
189  #markerline = svg.add( svg.polyline(points=marker_points, fill='none', stroke=traj_color, stroke_width=10, opacity=0.0 ) )
190  #arrow = arrowMarker(traj_color)
191  #markerline.set_markers( (arrow, arrow, arrow) )
192  #line.set_markers( (arrow, arrow, arrow) )
193  #line['marker-start'] = arrow.get_funciri()
194 
195 
196  # Add Start and Goal Point
197  start_pose = feedbackMsg.trajectories[0].trajectory[0].pose
198  goal_pose = feedbackMsg.trajectories[0].trajectory[len(feedbackMsg.trajectories[0].trajectory)-1].pose
199  start_position = start_pose.position
200  goal_position = goal_pose.position
201  svg.add(svg.circle(center=(start_position.x*SCALE,-start_position.y*SCALE), r=10, stroke_width=1, stroke='blue', fill ='blue'))
202  svg.add(svg.text("Start", (start_position.x*SCALE-70, -start_position.y*SCALE+45), font_size=35)) # Add label
203  svg.add(svg.circle(center=(goal_position.x*SCALE,-goal_position.y*SCALE), r=10, stroke_width=1, stroke='red', fill ='red'))
204  svg.add(svg.text("Goal", (goal_position.x*SCALE-40, -goal_position.y*SCALE+45), font_size=35)) # Add label
205 
206  # draw start arrow
207  start_arrow = svg.polyline([(0,-1),(6,-1),(5,-5),(15,0),(5,5),(6,1),(0,1)], fill='blue', opacity=1.0)
208  start_arrow.translate(start_position.x*SCALE,-start_position.y*SCALE)
209  start_arrow.rotate( quaternion2YawDegree(start_pose.orientation) )
210  start_arrow.scale(3)
211  svg.add(start_arrow)
212 
213  # draw goal arrow
214  goal_arrow = svg.polyline([(0,-1),(6,-1),(5,-5),(15,0),(5,5),(6,1),(0,1)], fill='red', opacity=1.0)
215  goal_arrow.translate(goal_position.x*SCALE,-goal_position.y*SCALE)
216  goal_arrow.rotate( quaternion2YawDegree(goal_pose.orientation) )
217  goal_arrow.scale(3)
218  svg.add(goal_arrow)
219 
220  # Draw obstacles
221  for obstacle in feedbackMsg.obstacles:
222  if len(obstacle.polygon.points) == 1: # point obstacle
223  point = obstacle.polygon.points[0]
224  svg.add(svg.circle(center=(point.x*SCALE,-point.y*SCALE), r=OBSTACLE_DIST, stroke_width=1, stroke='grey', fill ='grey', opacity=0.3))
225  svg.add(svg.circle(center=(point.x*SCALE,-point.y*SCALE), r=15, stroke_width=1, stroke='black', fill ='black'))
226  svg.add(svg.text("Obstacle", (point.x*SCALE-70, -point.y*SCALE+45), font_size=35)) # Add label
227  if len(obstacle.polygon.points) == 2: # line obstacle
228  line_start = obstacle.polygon.points[0]
229  line_end = obstacle.polygon.points[1]
230  svg.add(svg.line(start=(line_start.x*SCALE,-line_start.y*SCALE), end=(line_end.x*SCALE,-line_end.y*SCALE), stroke='black', fill='gray', stroke_width=1, opacity=1.0))
231  svg.add(svg.text("Obstacle", (line_start.x*SCALE-70, -line_start.y*SCALE+45), font_size=35)) # Add label
232  if len(obstacle.polygon.points) > 2: # polygon obstacle
233  vertices = []
234  for point in obstacle.polygon.points:
235  vertices.append((point.x*SCALE, -point.y*SCALE))
236  svg.add(svg.polygon(points=vertices, stroke='black', fill='gray', stroke_width=1, opacity=1.0))
237  svg.add(svg.text("Obstacle", (obstacle.polygon.points[0].x*SCALE-70, -obstacle.polygon.points.y*SCALE+45), font_size=35)) # Add label
238 
239 
240 
241  # Save svg to file (svg_output.svg) and exit node
242  svg.save()
243 
244  rospy.loginfo("Drawing completed.")
export_to_svg.sign
def sign(number)
Definition: export_to_svg.py:45
export_to_svg.quaternion2YawDegree
def quaternion2YawDegree(orientation)
Definition: export_to_svg.py:69
export_to_svg.arrowMarker
def arrowMarker(color='green', orientation='auto')
Definition: export_to_svg.py:56
export_to_svg.feedback_callback
feedback_callback
Definition: export_to_svg.py:107


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:15