Module: graphics
This module newly introduces revised graphics functions, coherent with Exudyn terminology; it provides basic graphics elements like cuboid, cylinder, sphere, solid of revolution, etc.; offers also some advanced functions for STL import and mesh manipulation; for some advanced functions see graphicsDataUtilties; GraphicsData helper functions generate dictionaries which contain line, text or triangle primitives for drawing in Exudyn using OpenGL.
Author: Johannes Gerstmayr
Date: 2024-05-10 (created)
Function: Sphere
Sphere(point = [0,0,0]
, radius = 0.1
, color = [0.,0.,0.,1.]
, nTiles = 8
, addEdges = False
, edgeColor = color.black
, addFaces = True
)
- function description:generate graphics data for a sphere with point p and radius
- input:
point
: center of sphere (3D list or np.array)radius
: positive valuecolor
: provided as list of 4 RGBA valuesnTiles
: used to determine resolution of sphere >=3; use larger values for finer resolutionaddEdges
: True or number of edges along sphere shell (under development); for optimal drawing, nTiles shall be multiple of 4 or 8edgeColor
: optional color for edgesaddFaces
: if False, no faces are added (only edges) - output:graphicsData dictionary, to be used in visualization of EXUDYN objects
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
bicycleIftommBenchmark.py (Ex), bungeeJump.py (Ex), chatGPTupdate.py (Ex), graphicsDataExample.py (Ex), humanRobotInteraction.py (Ex), connectorGravityTest.py (TM), contactCoordinateTest.py (TM), coordinateVectorConstraint.py (TM)
Function: Lines
Lines(pList
, color = [0.,0.,0.,1.]
)
- function description:generate graphics data for lines, given by list of points and color; transforms to GraphicsData dictionary
- input:
pList
: list of 3D numpy arrays or lists (to achieve closed curve, set last point equal to first point)color
: provided as list of 4 RGBA values - output:graphicsData dictionary, to be used in visualization of EXUDYN objects
- example:
#create simple 3-point lines
gLine=graphics.Lines([[0,0,0],[1,0,0],[2,0.5,0]], color=color.red)
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
ANCFcontactCircle2.py (Ex), doublePendulum2D.py (Ex), rigid3Dexample.py (Ex), simple4linkPendulumBing.py (Ex), doublePendulum2DControl.py (TM), genericJointUserFunctionTest.py (TM), rigidBodyCOMtest.py (TM), sphericalJointTest.py (TM)
Function: Circle
Circle(point = [0,0,0]
, radius = 1
, color = [0.,0.,0.,1.]
)
- function description:generate graphics data for a single circle; currently the plane normal = [0,0,1], just allowing to draw planar circles – this may be extended in future!
- input:
point
: center point of circleradius
: radius of circlecolor
: provided as list of 4 RGBA values - output:graphicsData dictionary, to be used in visualization of EXUDYN objects
- notes:the tiling (number of segments to draw circle) can be adjusted by visualizationSettings.general.circleTiling
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
ANCFcontactCircle2.py (Ex), NGsolvePistonEngine.py (Ex)
Function: Text
Text(point = [0,0,0]
, text = ''
, color = [0.,0.,0.,1.]
)
- function description:generate graphics data for a text drawn at a 3D position
- input:
point
: position of texttext
: string representing textcolor
: provided as list of 4 RGBA values**nodes
: text size can be adjusted with visualizationSettings.general.textSize, which affects the text size (=font size) globally - output:graphicsData dictionary, to be used in visualization of EXUDYN objects
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
ANCFcontactCircle2.py (Ex), NGsolveGeometry.py (Ex)
Function: Cuboid
Cuboid(pList
, color = [0.,0.,0.,1.]
, faces = [1,1,1,1,1,1]
, addNormals = False
, addEdges = False
, edgeColor = color.black
, addFaces = True
)
- function description:generate graphics data for general block with endpoints, according to given vertex definition
- input:
pList
: is a list of points [[x0,y0,z0],[x1,y1,z1],…]color
: provided as list of 4 RGBA valuesfaces
: includes the list of six binary values (0/1), denoting active faces (value=1); set index to zero to hide faceaddNormals
: if True, normals are added and there are separate points for every triangleaddEdges
: if True, edges are added in TriangleList of GraphicsDataedgeColor
: optional color for edgesaddFaces
: if False, no faces are added (only edges) - output:graphicsData dictionary, to be used in visualization of EXUDYN objects
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
addPrismaticJoint.py (Ex), addRevoluteJoint.py (Ex), ANCFrotatingCable2D.py (Ex), bungeeJump.py (Ex), chatGPTupdate.py (Ex), bricardMechanism.py (TM), carRollingDiscTest.py (TM), complexEigenvaluesTest.py (TM)
Function: BrickXYZ
BrickXYZ(xMin
, yMin
, zMin
, xMax
, yMax
, zMax
, color = [0.,0.,0.,1.]
, addNormals = False
, addEdges = False
, edgeColor = color.black
, addFaces = True
)
- function description:generate graphics data for orthogonal 3D block with min and max dimensions
- input:
x/y/z/Min/Max
: minimal and maximal cartesian coordinates for orthogonal cubecolor
: list of 4 RGBA valuesaddNormals
: add face normals to triangle informationaddEdges
: if True, edges are added in TriangleList of GraphicsDataedgeColor
: optional color for edgesaddFaces
: if False, no faces are added (only edges) - output:graphicsData dictionary, to be used in visualization of EXUDYN objects
- notes:DEPRECATED
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
Function: Brick
Brick(centerPoint = [0,0,0]
, size = [0.1,0.1,0.1]
, color = [0.,0.,0.,1.]
, addNormals = False
, addEdges = False
, edgeColor = color.black
, addFaces = True
)
- function description:generate graphics data forfor orthogonal 3D block with center point and size
- input:
centerPoint
: center of cube as 3D list or np.arraysize
: size as 3D list or np.arraycolor
: list of 4 RGBA valuesaddNormals
: add face normals to triangle informationaddEdges
: if True, edges are added in TriangleList of GraphicsDataedgeColor
: optional color for edgesaddFaces
: if False, no faces are added (only edges) - output:graphicsData dictionary, to be used in visualization of EXUDYN objects; if addEdges=True, it returns a list of two dictionaries
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
addPrismaticJoint.py (Ex), addRevoluteJoint.py (Ex), ANCFrotatingCable2D.py (Ex), beltDrivesComparison.py (Ex), bicycleIftommBenchmark.py (Ex), bricardMechanism.py (TM), carRollingDiscTest.py (TM), complexEigenvaluesTest.py (TM)
Function: Cylinder
Cylinder(pAxis = [0,0,0]
, vAxis = [0,0,1]
, radius = 0.1
, color = [0.,0.,0.,1.]
, nTiles = 16
, angleRange = [0,2*pi]
, lastFace = True
, cutPlain = True
, addEdges = False
, edgeColor = color.black
, addFaces = True
, **kwargs
)
- function description:generate graphics data for a cylinder with given axis, radius and color; nTiles gives the number of tiles (minimum=3)
- input:
pAxis
: axis point of one face of cylinder (3D list or np.array)vAxis
: vector representing the cylinder’s axis (3D list or np.array)radius
: positive value representing radius of cylindercolor
: provided as list of 4 RGBA valuesnTiles
: used to determine resolution of cylinder >=3; use larger values for finer resolutionangleRange
: given in rad, to draw only part of cylinder (halfcylinder, etc.); for full range use [0..2 * pi]lastFace
: if angleRange != [0,2*pi], then the faces of the open cylinder are shown with lastFace = TruecutPlain
: only used for angleRange != [0,2*pi]; if True, a plane is cut through the part of the cylinder; if False, the cylinder becomes a cake shape …addEdges
: if True, edges are added in TriangleList of GraphicsData; if addEdges is integer, additional int(addEdges) lines are added on the cylinder mantleedgeColor
: optional color for edgesaddFaces
: if False, no faces are added (only edges)alternatingColor
: if given, optionally another color in order to see rotation of solid; only works, if angleRange=[0,2*pi] - output:graphicsData dictionary, to be used in visualization of EXUDYN objects
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
beltDriveALE.py (Ex), beltDriveReevingSystem.py (Ex), beltDrivesComparison.py (Ex), bicycleIftommBenchmark.py (Ex), CMSexampleCourse.py (Ex), ANCFbeltDrive.py (TM), ANCFgeneralContactCircle.py (TM), carRollingDiscTest.py (TM)
Function: RigidLink
RigidLink(p0
, p1
, axis0 = [0,0,0]
, axis1 = [0,0,0]
, radius = [0.1,0.1]
, thickness = 0.05
, width = [0.05,0.05]
, color = [0.,0.,0.,1.]
, nTiles = 16
)
- function description:generate graphics data for a planar Link between the two joint positions, having two axes
- input:
p0
: joint0 center positionp1
: joint1 center positionaxis0
: direction of rotation axis at p0, if drawn as a cylinder; [0,0,0] otherwiseaxis1
: direction of rotation axis of p1, if drawn as a cylinder; [0,0,0] otherwiseradius
: list of two radii [radius0, radius1], being the two radii of the joints drawn by a cylinder or spherewidth
: list of two widths [width0, width1], being the two widths of the joints drawn by a cylinder; ignored for spherethickness
: the thickness of the link (shaft) between the two joint positions; thickness in z-direction or diameter (cylinder)color
: provided as list of 4 RGBA valuesnTiles
: used to determine resolution of cylinder >=3; use larger values for finer resolution - output:graphicsData dictionary, to be used in visualization of EXUDYN objects
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
fourBarMechanism3D.py (Ex), geneticOptimizationSliderCrank.py (Ex), multiMbsTest.py (Ex), openVRengine.py (Ex), pistonEngine.py (Ex), fourBarMechanismIftomm.py (TM), rollingDiscTangentialForces.py (TM), sliderCrank3Dbenchmark.py (TM)
Function: SolidOfRevolution
SolidOfRevolution(pAxis
, vAxis
, contour
, color = [0.,0.,0.,1.]
, nTiles = 16
, smoothContour = False
, addEdges = False
, edgeColor = color.black
, addFaces = True
, **kwargs
)
- function description:generate graphics data for a solid of revolution with given 3D point and axis, 2D point list for contour, (optional)2D normals and color;
- input:
pAxis
: axis point of one face of solid of revolution (3D list or np.array)vAxis
: vector representing the solid of revolution’s axis (3D list or np.array)contour
: a list of 2D-points, specifying the contour (x=axis, y=radius), e.g.: [[0,0],[0,0.1],[1,0.1]]color
: provided as list of 4 RGBA valuesnTiles
: used to determine resolution of solid; use larger values for finer resolutionsmoothContour
: if True, the contour is made smooth by auto-computing normals to the contouraddEdges
: True or number of edges along revolution mantle; for optimal drawing, nTiles shall be multiple addEdgesedgeColor
: optional color for edgesaddFaces
: if False, no faces are added (only edges)alternatingColor
: add a second color, which enables to see the rotation of the solid - output:graphicsData dictionary, to be used in visualization of EXUDYN objects
- example:
#simple contour, using list of 2D points:
contour=[[0,0.2],[0.3,0.2],[0.5,0.3],[0.7,0.4],[1,0.4],[1,0.]]
rev1 = graphics.SolidOfRevolution(pAxis=[0,0.5,0], vAxis=[1,0,0],
contour=contour, color=color.red,
alternatingColor=color.grey)
#draw torus:
contour=[]
r = 0.2 #small radius of torus
R = 0.5 #big radius of torus
nc = 16 #discretization of torus
for i in range(nc+3): #+3 in order to remove boundary effects
contour+=[[r*cos(i/nc*pi*2),R+r*sin(i/nc*pi*2)]]
#use smoothContour to make torus looking smooth
rev2 = graphics.SolidOfRevolution(pAxis=[0,0.5,0], vAxis=[1,0,0],
contour=contour, color=color.red,
nTiles = 64, smoothContour=True)
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
graphicsDataExample.py (Ex), gyroStability.py (Ex), particlesSilo.py (Ex), serialRobotKinematicTreeDigging.py (Ex), ConvexContactTest.py (TM)
Function: Arrow
Arrow(pAxis
, vAxis
, radius
, color = [0.,0.,0.,1.]
, headFactor = 2
, headStretch = 4
, nTiles = 12
)
- function description:generate graphics data for an arrow with given origin, axis, shaft radius, optional size factors for head and color; nTiles gives the number of tiles (minimum=3)
- input:
pAxis
: axis point of the origin (base) of the arrow (3D list or np.array)vAxis
: vector representing the vector pointing from the origin to the tip (head) of the error (3D list or np.array)radius
: positive value representing radius of shaft cylinderheadFactor
: positive value representing the ratio between head’s radius and the shaft radiusheadStretch
: positive value representing the ratio between the head’s radius and the head’s lengthcolor
: provided as list of 4 RGBA valuesnTiles
: used to determine resolution of arrow (of revolution object) >=3; use larger values for finer resolution - output:graphicsData dictionary, to be used in visualization of EXUDYN objects
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
beltDriveALE.py (Ex), beltDriveReevingSystem.py (Ex), beltDrivesComparison.py (Ex), graphicsDataExample.py (Ex), reevingSystem.py (Ex), ACFtest.py (TM), ANCFbeltDrive.py (TM), ANCFgeneralContactCircle.py (TM)
Function: Basis
Basis(origin = [0,0,0]
, rotationMatrix = np.eye(3)
, length = 1
, colors = [color.red, color.green, color.blue]
, headFactor = 2
, headStretch = 4
, nTiles = 12
, **kwargs
)
- function description:generate graphics data for three arrows representing an orthogonal basis with point of origin, shaft radius, optional size factors for head and colors; nTiles gives the number of tiles (minimum=3)
- input:
origin
: point of the origin of the base (3D list or np.array)rotationMatrix
: optional transformation, which rotates the basis vectorslength
: positive value representing lengths of arrows for basiscolors
: provided as list of 3 colors (list of 4 RGBA values)headFactor
: positive value representing the ratio between head’s radius and the shaft radiusheadStretch
: positive value representing the ratio between the head’s radius and the head’s lengthnTiles
: used to determine resolution of arrows of basis (of revolution object) >=3; use larger values for finer resolutionradius
: positive value representing radius of arrows; default: radius = 0.01*length - output:graphicsData dictionary, to be used in visualization of EXUDYN objects
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
fourBarMechanism3D.py (Ex), graphicsDataExample.py (Ex), gyroStability.py (Ex), InverseKinematicsNumericalExample.py (Ex), mobileMecanumWheelRobotWithLidar.py (Ex), bricardMechanism.py (TM), distanceSensor.py (TM), explicitLieGroupIntegratorTest.py (TM)
Function: Frame
Frame(HT = np.eye(4)
, length = 1
, colors = [color.red, color.green, color.blue]
, headFactor = 2
, headStretch = 4
, nTiles = 12
, **kwargs
)
- function description:generate graphics data for frame (similar to Basis), showing three arrows representing an orthogonal basis for the homogeneous transformation HT; optional shaft radius, optional size factors for head and colors; nTiles gives the number of tiles (minimum=3)
- input:
HT
: homogeneous transformation representing framelength
: positive value representing lengths of arrows for basiscolors
: provided as list of 3 colors (list of 4 RGBA values)headFactor
: positive value representing the ratio between head’s radius and the shaft radiusheadStretch
: positive value representing the ratio between the head’s radius and the head’s lengthnTiles
: used to determine resolution of arrows of basis (of revolution object) >=3; use larger values for finer resolutionradius
: positive value representing radius of arrows; default: radius = 0.01*length - output:graphicsData dictionary, to be used in visualization of EXUDYN objects
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
serialRobotInverseKinematics.py (Ex), ACFtest.py (TM)
Function: Quad
Quad(pList
, color = [0.,0.,0.,1.]
, **kwargs
)
- function description:generate graphics data for simple quad with option for checkerboard pattern;points are arranged counter-clock-wise, e.g.: p0=[0,0,0], p1=[1,0,0], p2=[1,1,0], p3=[0,1,0]
- input:
pList
: list of 4 quad points [[x0,y0,z0],[x1,y1,z1],…]color
: provided as list of 4 RGBA valuesalternatingColor
: second color; if defined, a checkerboard pattern (default: 10x10) is drawn with color and alternatingColornTiles
: number of tiles for checkerboard pattern (default: 10)nTilesY
: if defined, use number of tiles in y-direction different from x-direction (=nTiles) - output:graphicsData dictionary, to be used in visualization of EXUDYN objects
- example:
plane = graphics.Quad([[-8, 0, -8],[ 8, 0, -8,],[ 8, 0, 8],[-8, 0, 8]],
color.darkgrey, nTiles=8,
alternatingColor=color.lightgrey)
oGround=mbs.AddObject(ObjectGround(referencePosition=[0,0,0],
visualization=VObjectGround(graphicsData=[plane])))
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
massSpringFrictionInteractive.py (Ex), nMassOscillator.py (Ex), nMassOscillatorEigenmodes.py (Ex), nMassOscillatorInteractive.py (Ex), simulateInteractively.py (Ex)
Function: CheckerBoard
CheckerBoard(point = [0,0,0]
, normal = [0,0,1]
, size = 1
, color = color.lightgrey
, alternatingColor = color.lightgrey2
, nTiles = 10
, **kwargs
)
- function description:function to generate checkerboard background;points are arranged counter-clock-wise, e.g.:
- input:
point
: midpoint of pattern provided as list or np.arraynormal
: normal to plane provided as list or np.arraysize
: dimension of first side length of quadsize2
: dimension of second side length of quadcolor
: provided as list of 4 RGBA valuesalternatingColor
: second color; if defined, a checkerboard pattern (default: 10x10) is drawn with color and alternatingColornTiles
: number of tiles for checkerboard pattern in first directionnTiles2
: number of tiles for checkerboard pattern in second direction; default: nTiles - output:graphicsData dictionary, to be used in visualization of EXUDYN objects
- example:
plane = graphics.CheckerBoard(normal=[0,0,1], size=5)
oGround=mbs.AddObject(ObjectGround(referencePosition=[0,0,0],
visualization=VObjectGround(graphicsData=[plane])))
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
ANCFrotatingCable2D.py (Ex), bicycleIftommBenchmark.py (Ex), chatGPTupdate.py (Ex), chatGPTupdate2.py (Ex), craneReevingSystem.py (Ex), ANCFoutputTest.py (TM), bricardMechanism.py (TM), connectorGravityTest.py (TM)
Function: SolidExtrusion
SolidExtrusion(vertices
, segments
, height
, rot = np.diag([1,1,1])
, pOff = [0,0,0]
, color = [0,0,0,1]
, smoothNormals = False
, addEdges = False
, edgeColor = color.black
, addFaces = True
)
- function description:create graphicsData for solid extrusion based on 2D points and segments; by default, the extrusion is performed in z-direction;additional transformations are possible to translate and rotate the extruded body;
- input:
vertices
: list of pairs of coordinates of vertices in mesh [x,y], see ComputeTriangularMesh(…)segments
: list of segments, which are pairs of node numbers [i,j], defining the boundary of the mesh;the ordering of the nodes is such that left triangle = inside, right triangle = outside; see ComputeTriangularMesh(…)height
: height of extruded objectrot
: rotation matrix, which the extruded object point coordinates are multiplied with before adding offsetpOff
: 3D offset vector added to extruded coordinates; the z-coordinate of the extrusion object obtains 0 for the base plane, z=height for the top planesmoothNormals
: if True, algorithm tries to smoothen normals at vertices and normals are added; creates more points; if False, triangle normals are used internallyaddEdges
: if True or 1, edges at bottom/top are included in the GraphicsData dictionary; if 2, also mantle edges are includededgeColor
: optional color for edgesaddFaces
: if False, no faces are added (only edges) - output:graphicsData dictionary, to be used in visualization of EXUDYN objects
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
Function: FromPointsAndTrigs
FromPointsAndTrigs(points
, triangles
, color = [0.,0.,0.,1.]
)
- function description:convert triangles and points as returned from graphics.ToPointsAndTrigs(…)
- input:
points
: list of np.array with 3 floats per pointtriangles
: list of np.array with 3 int per triangle (0-based indices to triangles)color
: provided as list of 4 RGBA values or single list of (number of points)*[4 RGBA values] - output:returns GraphicsData with type TriangleList
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
NGsolveGeometry.py (Ex), particlesSilo.py (Ex), distanceSensor.py (TM), generalContactFrictionTests.py (TM), generalContactImplicit1.py (TM), generalContactImplicit2.py (TM)
Function: ToPointsAndTrigs
- function description:convert graphics data into list of points and list of triangle indices (triplets)
- input:g contains a GraphicsData with type TriangleList
- output:returns [points, triangles], with points as list of np.array with 3 floats per point and triangles as a list of np.array with 3 int per triangle (0-based indices to points)
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
mobileMecanumWheelRobotWithLidar.py (Ex), particleClusters.py (Ex), particlesSilo.py (Ex), reinforcementLearningRobot.py (Ex), serialRobotKinematicTreeDigging.py (Ex), distanceSensor.py (TM), generalContactCylinderTest.py (TM), generalContactCylinderTrigsTest.py (TM)
Function: Move
Move(g
, pOff
, Aoff
)
- function description:add rigid body transformation to GraphicsData, using position offset (global) pOff (list or np.array) and rotation Aoff (transforms local to global coordinates; list of lists or np.array); see Aoff how to scale coordinates!
- input:
g
: graphicsData to be transformedpOff
: 3D offset as list or numpy.array added to rotated pointsAoff
: 3D rotation matrix as list of lists or numpy.array with shape (3,3); if A is scaled by factor, e.g. using 0.001*np.eye(3), you can also scale the coordinates!!! - output:returns new graphcsData object to be used for drawing in objects
- notes:transformation corresponds to HomogeneousTransformation(Aoff, pOff), transforming original coordinates v into vNew = pOff + Aoff @ v
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
graphicsDataExample.py (Ex), humanRobotInteraction.py (Ex), kinematicTreeAndMBS.py (Ex), openVRengine.py (Ex), pistonEngine.py (Ex), rigidBodyAsUserFunctionTest.py (TM)
Function: MergeTriangleLists
MergeTriangleLists(g1
, g2
)
- function description:merge 2 different graphics data with triangle lists
- input:graphicsData dictionaries g1 and g2 obtained from GraphicsData functions
- output:one graphicsData dictionary with single triangle lists and compatible points and normals, to be used in visualization of EXUDYN objects; edges are merged; edgeColor is taken from graphicsData g1
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
graphicsDataExample.py (Ex), mobileMecanumWheelRobotWithLidar.py (Ex), particleClusters.py (Ex), particlesSilo.py (Ex), serialRobotKinematicTreeDigging.py (Ex), distanceSensor.py (TM), generalContactFrictionTests.py (TM), laserScannerTest.py (TM)
Function: FromSTLfileASCII
FromSTLfileASCII(fileName
, color = [0.,0.,0.,1.]
, verbose = False
, invertNormals = True
, invertTriangles = True
)
- function description:generate graphics data from STL file (text format!) and use color for visualization; this function is slow, use stl binary files with FromSTLfile(…)
- input:
fileName
: string containing directory and filename of STL-file (in text / SCII format) to loadcolor
: provided as list of 4 RGBA valuesverbose
: if True, useful information is provided during readinginvertNormals
: if True, orientation of normals (usually pointing inwards in STL mesh) are inverted for compatibility in ExudyninvertTriangles
: if True, triangle orientation (based on local indices) is inverted for compatibility in Exudyn - output:creates graphicsData, inverting the STL graphics regarding normals and triangle orientations (interchanged 2nd and 3rd component of triangle index)
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
stlFileImport.py (Ex)
Function: FromSTLfile
FromSTLfile(fileName
, color = [0.,0.,0.,1.]
, verbose = False
, density = 0.
, scale = 1.
, Aoff = []
, pOff = []
, invertNormals = True
, invertTriangles = True
)
- function description:generate graphics data from STL file, allowing text or binary format; requires numpy-stl to be installed; additionally can scale, rotate and translate
- input:
fileName
: string containing directory and filename of STL-file (in text / SCII format) to loadcolor
: provided as list of 4 RGBA valuesverbose
: if True, useful information is provided during readingdensity
: if given and if verbose, mass, volume, inertia, etc. are computedscale
: point coordinates are transformed by scaling factorinvertNormals
: if True, orientation of normals (usually pointing inwards in STL mesh) are inverted for compatibility in ExudyninvertTriangles
: if True, triangle orientation (based on local indices) is inverted for compatibility in Exudyn - output:creates graphicsData, inverting the STL graphics regarding normals and triangle orientations (interchanged 2nd and 3rd component of triangle index)
- notes:the model is first scaled, then rotated, then the offset pOff is added; finally min, max, mass, volume, inertia, com are computed!
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
humanRobotInteraction.py (Ex), ROSTurtle.py (Ex), stlFileImport.py (Ex)
Function: AddEdgesAndSmoothenNormals
AddEdgesAndSmoothenNormals(graphicsData
, edgeColor = color.black
, edgeAngle = 0.25*pi
, pointTolerance = 5
, addEdges = True
, smoothNormals = True
, roundDigits = 5
, triangleColor = []
)
- function description:compute and return GraphicsData with edges and smoothend normals for mesh consisting of points and triangles (e.g., as returned from GraphicsData2PointsAndTrigs)
graphicsData
: single GraphicsData object of type TriangleList; existing edges are ignorededgeColor
: optional color for edgesedgeAngle
: angle above which edges are added to geometryroundDigits
: number of digits, relative to max dimensions of object, at which points are assumed to be equalsmoothNormals
: if True, algorithm tries to smoothen normals at vertices; otherwise, uses triangle normalsaddEdges
: if True, edges are added in TriangleList of GraphicsDatatriangleColor
: if triangleColor is set to a RGBA color, this color is used for the new triangle mesh throughout - output:returns GraphicsData with added edges and smoothed normals
- notes:this function is suitable for STL import; it assumes that all colors in graphicsData are the same and only takes the first color!
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
humanRobotInteraction.py (Ex), NGsolveGeometry.py (Ex), stlFileImport.py (Ex)
Function: ExportSTL
ExportSTL(graphicsData
, fileName
, solidName = 'ExudynSolid'
, invertNormals = True
, invertTriangles = True
)
- function description:export given graphics data (only type TriangleList allowed!) to STL ascii file using fileName
- input:
graphicsData
: a single GraphicsData dictionary with type=’TriangleList’, no list of GraphicsDatafileName
: file name including (local) path to export STL filesolidName
: optional name used in STL fileinvertNormals
: if True, orientation of normals (usually pointing inwards in STL mesh) are inverted for compatibility in ExudyninvertTriangles
: if True, triangle orientation (based on local indices) is inverted for compatibility in Exudyn
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
stlFileImport.py (Ex)