Skip to content

Commit ca51ef5

Browse files
authored
Merge pull request petercorke#33 from petercorke/micah-dev
Micah dev
2 parents f6cdf65 + c4f07b2 commit ca51ef5

18 files changed

+74680
-1
lines changed

graphics/README.md

Lines changed: 259 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,259 @@
1+
This folder contains the graphics functionality of the toolbox.
2+
Instructions on how to use the graphical section of the toolbox below.
3+
(Pictures to come)
4+
5+
# TODO
6+
* Robot Joints
7+
* Rotational Joint
8+
* Prismatic Joint
9+
* ~~Static Joint~~
10+
* Gripper Joint
11+
* Grid Updating
12+
* On rotation/move finish
13+
* ~~Don't redraw labels, move/update them~~
14+
* Don't redraw the grid, move/update them
15+
* Error handling
16+
* ~~Throw custom error messages~~
17+
* Handle vpython error messages
18+
* STL
19+
* Load Binary STL files
20+
* Option to save a mesh to STL?
21+
* 2D Graphics
22+
* Will likely not be done in vpython (overkill)
23+
24+
# Future Additions
25+
* Updated Canvas Controls
26+
* WASD-QE controls (move/rotate)
27+
* Mouse rotation
28+
* Webpage Controls
29+
* Buttons that allow toggling display options
30+
* Labels, reference frames, robot, etc
31+
* Robot Interaction
32+
* Use the mouse/keyboard to manually rotate/move joints
33+
34+
# How To
35+
## Common Functionality
36+
VPython has its own data types that have been used. Firstly, the `radians()`, and `degrees()` functions convert between radians and degrees.
37+
The `vector` class is also very crucial to the graphics. It can either represent a vector or a 3D point.
38+
39+
For convenience, some functions and variables are provided for easy use. `wrap_to_pi()` takes in an angle, and specification on degrees or radians. It returns the respective angle between -pi and pi.
40+
Three vectors are also supplied for readability to ensure correct axes are used when referencing. `x_axis_vector`, `y_axis_vector`, `z_axis_vector` can be used when supplying the rotation axis, for example.
41+
```python
42+
# Rotate the joint around its local x-axis by 30 degrees
43+
rot_link.rotate_around_joint_axis(radians(30), x_axis_vector)
44+
```
45+
46+
## Setting Up The Scene
47+
Firstly, import the model_puma560 file to import all files/packages used within the graphics (imports are used within other files).
48+
```python
49+
from graphics.model_puma560 import *
50+
```
51+
Any use of VPython objects requires a scene.
52+
53+
To create a scene to draw object to, a canvas must be created. Upon creation, a localhost http server will be opened. The function will return a GraphicsGrid object.
54+
55+
Different attributes can be supplied to the function for some customisation. The display width, height, title, and caption can be manually input. Lastly, a boolean representing the grid visibility can be set.
56+
```python
57+
# Create a default canvas (1000*500, with grid displayed, no title or caption)
58+
canvas_grid = init_canvas()
59+
60+
# Alternatively create a grid with specified parameters
61+
canvas_grid = init_canvas(height=768, width=1024, title="Scene 1", caption="This scene shows...", grid=False)
62+
```
63+
The GraphicsGrid object has functions to update the visual, or to toggle visibility.
64+
```python
65+
# Update the grids to relocate/reorient to the camera focus point
66+
canvas_grid.update_grid()
67+
68+
# Turn off the visual display of the grid
69+
canvas_grid.set_visibility(False)
70+
```
71+
Now that the scene is created, a robot must be created to be displayed.
72+
73+
## Displaying Robot Joints
74+
If you want to use the example puma560 robot, simply call the creation function that will return a GraphicalRobot object. It will automatically be displayed in the canvas
75+
```python
76+
# Import the puma560 models and return a GraphicalRobot object
77+
puma560 = import_puma_560()
78+
```
79+
80+
Creating your own robot is just as easy with the ability to use STL objects for your own custom robot, or using simple line segments.
81+
Importing the STL objects is described below. Once you have the created 3D objects from the import, they can be used in the constructors.
82+
83+
Firstly, decide which type of joint you require: `RotationalJoint`, `PrismaticJoint`, `StaticJoint`, `Gripper`.
84+
85+
All joint types can be supplied with an `x_axis` parameter. Defaulting to `x_axis_vector`, this variable simply states which direction in space the object's current x-axis is pointing in. This allows alignment of reference frames, for example that objects aren't used sideways.
86+
87+
Rotational joints have an independent attribute `rotation_axis` to assign which axis the joint rotates about, defaulting to `y_axis_vector`.
88+
89+
If using an STL object, the connection parameters are the 3D points in space (real coordinates of where the object is currently) that correspond to the positions where the neighbour joints connect to it.
90+
For example, if the object is currently loaded in with the point where it would connect to a previous segment at (0, 0, 0), and the 'tooltip' or point it would connect to the next joint at (1, 0, 0), the creation would look like
91+
```python
92+
# Current connection points
93+
connect_from = vector(0, 0, 0)
94+
connect_to = vector(1, 0, 0)
95+
96+
# Create a Rotational joint that is currently facing in the +x direction, that rotates about it's y-axis
97+
new_link = RotationalJoint(connect_from,
98+
connect_to,
99+
x_axis=x_axis_vector,
100+
rotation_axis=y_axis_vector,
101+
graphic_obj=your_stl_obj)
102+
```
103+
Otherwise if no prior 3D object is given, a line segment will be created to render as the joint. The `x_axis` attribute is not used in this situation.
104+
```python
105+
# The current joint will go from (1, 1, 0) to (1, 1, 3)
106+
connect_from = vector(1, 1, 0)
107+
connect_to = vector(1, 1, 3)
108+
109+
# Create a basic rotation joint
110+
new_link = RotationalJoint(connect_from, connect_to)
111+
```
112+
113+
The other joint types are created in the same way
114+
```python
115+
# Connection points
116+
connect_from = vector(3, 0, 0)
117+
connect_to = vector(0, 0, 0)
118+
119+
# Create a prismatic joint with our without an STL object
120+
new_link_graphic = PrismaticJoint(connect_from,
121+
connect_to,
122+
x_axis=x_axis_vector,
123+
graphic_obj=your_stl_obj)
124+
new_link_basic = PrismaticJoint(connect_from, connect_to)
125+
126+
# Create a static joint with our without an STL object
127+
new_link_graphic = StaticJoint(connect_from,
128+
connect_to,
129+
x_axis=x_axis_vector,
130+
graphic_obj=your_stl_obj)
131+
new_link_basic = StaticJoint(connect_from, connect_to)
132+
133+
# Create a gripper joint with our without an STL object
134+
new_link_graphic = Gripper(connect_from,
135+
connect_to,
136+
x_axis=x_axis_vector,
137+
graphic_obj=your_stl_obj)
138+
new_link_basic = Gripper(connect_from, connect_to)
139+
```
140+
## Importing an STL
141+
Importing an STL can either be straight-forward or a bit tedious. Firstly, import the STL file into VPython using `import_object_from_stl()`.
142+
This will create a compound object from the triangles, and display it in the canvas.
143+
```python
144+
# Create a compound object from an STL file 'my_object'
145+
# The search path is relative to ./graphics/models/
146+
# Only the filename is required (no extension)
147+
my_mesh = import_object_from_stl('my_object')
148+
```
149+
Then depending on where the object triangles are configured from the file, it may need to be translated or rotated.
150+
151+
The Joint classes assume that the origin of the joint is the rotation point. However, creating a compound object puts the origin at the centre of the 3D bounding box.
152+
Since these positions may not align, translation and/or rotation may be required.
153+
154+
If the loaded object was not oriented correctly upon loading, it can be manually rotated (preferably before setting the origin described below).
155+
Manual inspection of the objects orientation will guide to how to rotate the object in space. They can be easily rotated through VPython's object rotate function
156+
```python
157+
# Load the mesh
158+
my_stl_obj = import_object_from_stl('my_object')
159+
160+
# Rotate the object about the +Y axis 90 degrees
161+
my_stl_obj.rotate(angle=radians(90), axis=y_axis_vector, origin=vector(0, 0, 0))
162+
```
163+
A function `set_stl_origin()` is also supplied to change the origin.
164+
This function takes in a graphical object, and two 3D points representing the world coordinates of where the desired origin currently is, and where the desired origin should be.
165+
166+
For example, if an STL object loads in and the origin is below (-z) where it should be, and the origin is at the bottom of the object, the following code will translate it up and set the origin.
167+
```python
168+
# Load the mesh
169+
my_stl_obj = import_object_from_stl('my_object')
170+
171+
# Find the coordinates of where the desired origin is
172+
# It's at the bottom of the object, that is entirely below the z=0 plane
173+
174+
# Z coordinate is located from the middle of the object, with an extra distance of half the object away.
175+
my_stl_obj_z_pos = my_stl_obj.pos.z - my_stl_obj.width/2
176+
# X and Y coordinates already in place
177+
current_origin_location = vector(my_stl_obj.pos.x, my_stl_obj.pos.y, my_stl_obj_z_pos)
178+
# Origin should be at current X, Y, with Z at 0
179+
required_origin_location = vector(my_stl_obj.pos.x, my_stl_obj.pos.y, 0)
180+
181+
# Update the STL object
182+
my_stl_obj = set_stl_origin(my_stl_obj, current_origin_location, required_origin_location)
183+
```
184+
The STL objects can now be used in the Joint classes without hassle.
185+
186+
## Creating a GraphicalRobot
187+
Now that you have created all of the robot links, a `GraphicalRobot` can be created. Simply inputting a list of the joints to the constructor is all that is required.
188+
189+
The order of joints is important! It is assumed that index 0 is the base, and incrementally goes through the robot from base to tooltip.
190+
```python
191+
# Create a default 3-link rotational robot along the +X axis.
192+
my_graphic_robot = GraphicalRobot([
193+
RotationalJoint(vector(0, 0, 0), vector(1, 0, 0)),
194+
RotationalJoint(vector(1, 0, 0), vector(2, 0, 0)),
195+
RotationalJoint(vector(2, 0, 0), vector(3, 0, 0))
196+
])
197+
```
198+
Or if 3D object meshes are used for links
199+
```python
200+
# Base Joint: Rotate +z axis, facing x-axis (def)
201+
base_joint = RotationalJoint(vector(0, 0, 0), vector(1, 0, 0), rotation_axis=z_axis_vector, graphic_obj=my_stl_object1),
202+
# Middle Joint: Rotate +y axis (def), facing x-axis (def)
203+
mid_joint = RotationalJoint(vector(1, 0, 0), vector(2, 0, 0), graphic_obj=my_stl_object2),
204+
# End Joint: Rotate +y axis (def), facing x-axis (def)
205+
end_joint = RotationalJoint(vector(2, 0, 0), vector(3, 0, 0), graphic_obj=my_stl_object3),
206+
207+
# Create a 3D mesh graphical robot
208+
my_graphic_robot = GraphicalRobot([
209+
base_joint,
210+
mid_joint,
211+
end_joint
212+
])
213+
```
214+
215+
## Using A GraphicalRobot
216+
The robot class has two functions that handle the display. One function each to toggle the visibility for the joints and reference frames.
217+
```python
218+
# Turn off the robots reference frame displays
219+
my_graphic_robot.set_reference_visibility(False)
220+
221+
# Toggle the robot visibility
222+
my_graphic_robot.set_robot_visibility(not my_graphic_robot.is_shown)
223+
```
224+
Moving the robot around in the 3D space is possible through `move_base()`. Given a 3D coordinate, the origin of the base will be relocated to this position.
225+
```python
226+
# Move the base of the robot to (2, 3, 0)
227+
my_graphic_robot.move_base(vector(2, 3, 0))
228+
```
229+
Setting joint angles can be done in two ways. Firstly, one joint can be rotated individually.
230+
The function takes the joint index (from the list of creation) and an angle (radians) to set the joint angle to. The angle given is it's local rotation angle.
231+
232+
If a joint that is not a rotational joint is given, an error will be displayed.
233+
```python
234+
joint_index = 1
235+
new_angle = radians(30)
236+
237+
# Rotate the 1st joint of the robot (base = 0) to an angle of 30 degrees
238+
my_graphic_robot.set_joint_angle(joint_index, new_angle)
239+
```
240+
Otherwise, all joint angles can be modified together.
241+
If the given list of angles doesn't match the number of joints, an error will be displayed.
242+
Further, while iterating through the joints, a message will appear saying a non-revolute was found. It will skip this joint and it's associated given angle.
243+
```python
244+
# Assuming a 3-joint all-rotational robot
245+
my_graphical_robot.set_all_joint_angles([
246+
radians(-45),
247+
radians(45),
248+
radians(15)
249+
])
250+
```
251+
252+
Lastly, a print function `print_joint_angles()` will print out the current local joint angles, if a revolute.
253+
If the output angles are to be displayed in degrees, True should be input as a parameter.
254+
```python
255+
# Print joint angles in radians
256+
my_graphical_robot.print_joint_angles()
257+
# Print joint angles in degrees
258+
my_graphical_robot.print_joint_angles(True)
259+
```

graphics/__init__.py

Whitespace-only changes.

graphics/common_functions.py

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
from vpython import radians, vector
2+
3+
x_axis_vector = vector(1, 0, 0)
4+
y_axis_vector = vector(0, 1, 0)
5+
z_axis_vector = vector(0, 0, 1)
6+
7+
8+
# TODO handle radians (needed more than degrees)
9+
def wrap_to_pi(angle):
10+
angle = angle % radians(360)
11+
if angle > radians(180):
12+
angle -= radians(360)
13+
return angle

graphics/graphics_canvas.py

Lines changed: 102 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,102 @@
1+
from graphics.graphics_grid import *
2+
from graphics.common_functions import *
3+
4+
5+
def init_canvas(height=500, width=1000, title='', caption='', grid=True):
6+
"""
7+
Set up the scene with initial conditions.
8+
- White background
9+
- Width, height
10+
- Title, caption
11+
- Axes drawn (if applicable)
12+
13+
:param height: Height of the canvas on screen (Pixels), defaults to 500.
14+
:type height: int, optional
15+
:param width: Width of the canvas on screen (Pixels), defaults to 1000.
16+
:type width: int, optional
17+
:param title: Title of the plot. Gets displayed above canvas, defaults to ''.
18+
:type title: str, optional
19+
:param caption: Caption (subtitle) of the plot. Gets displayed below the canvas, defaults to ''.
20+
:type caption: str, optional
21+
:param grid: Whether a grid should be displayed in the plot, defaults to `True`.
22+
:type grid: bool, optional
23+
:return: The graphics grid object for use outside canvas creation
24+
:rtype: class:`GraphicsGrid`
25+
"""
26+
27+
# Apply the settings
28+
scene.background = color.white
29+
scene.width = width
30+
scene.height = height
31+
scene.autoscale = False
32+
33+
if title != '':
34+
scene.title = title
35+
36+
if caption != '':
37+
scene.caption = caption
38+
39+
convert_grid_to_z_up()
40+
41+
graphics_grid = GraphicsGrid()
42+
graphics_grid.draw_grid()
43+
if not grid:
44+
graphics_grid.set_visibility(False)
45+
46+
return graphics_grid
47+
48+
49+
def convert_grid_to_z_up():
50+
"""
51+
Rotate the camera so that +z is up
52+
(Default vpython scene is +y up)
53+
"""
54+
# Place camera at center to aid rotations
55+
scene.camera.pos = vector(0, 0, 0)
56+
# Rotate about y then x axis
57+
# (Camera defaults looking in -z direction -> (0, 0, -1))
58+
scene.camera.rotate(radians(90), axis=y_axis_vector)
59+
scene.camera.rotate(radians(90), axis=x_axis_vector)
60+
# Place the camera in the + axes
61+
scene.camera.pos = vector(10, 10, 10)
62+
scene.camera.axis = -scene.camera.pos
63+
return
64+
65+
66+
def draw_reference_frame_axes(origin, x_axis_vector_dir, x_axis_rotation):
67+
"""
68+
Draw x, y, z axes from the given point.
69+
Each axis is represented in the objects reference frame.
70+
71+
:param origin: 3D vector representing the point to draw the reference from at.
72+
:type origin: class:`vpython.vector`
73+
:param x_axis_vector_dir: 3D vector representing the direction of the positive x axis.
74+
:type x_axis_vector_dir: class:`vpython.vector`
75+
:param x_axis_rotation: Angle in radians to rotate the frame around the x-axis.
76+
:type x_axis_rotation: float
77+
:return: Compound object of the 3 axis arrows.
78+
:rtype: class:`vpython.compound`
79+
"""
80+
81+
# Create Basic Frame
82+
# Draw X Axis
83+
x_arrow = arrow(pos=origin, axis=x_axis_vector, length=0.25, color=color.red)
84+
85+
# Draw Y Axis
86+
y_arrow = arrow(pos=origin, axis=y_axis_vector, length=0.25, color=color.green)
87+
88+
# Draw Z Axis
89+
z_arrow = arrow(pos=origin, axis=z_axis_vector, length=0.25, color=color.blue)
90+
91+
# Combine all to manipulate together
92+
# Set origin to where axis converge (instead of the middle of the resulting object bounding box)
93+
frame_ref = compound([x_arrow, y_arrow, z_arrow], origin=origin)
94+
95+
# Rotate frame around x, y, z axes as required
96+
# Set x-axis along required vector, and rotate around the x-axis to corresponding angle to align last two axes
97+
# NB: Set XY axis first, as vpython is +y up bias, objects rotate respective to this bias when setting axis
98+
frame_ref.axis = vector(x_axis_vector_dir.x, x_axis_vector_dir.y, 0)
99+
frame_ref.axis = x_axis_vector_dir
100+
frame_ref.rotate(angle=x_axis_rotation)
101+
102+
return frame_ref

0 commit comments

Comments
 (0)