diff --git a/src/prototype/DynamicsArchitecture/Actuator.py b/src/prototype/DynamicsArchitecture/Actuator.py new file mode 100644 index 0000000000..36ca9fb06a --- /dev/null +++ b/src/prototype/DynamicsArchitecture/Actuator.py @@ -0,0 +1,5 @@ + +class Actuator: + def __init__(self): + self.force = None + self.torque = None diff --git a/src/prototype/DynamicsArchitecture/Base.py b/src/prototype/DynamicsArchitecture/Base.py new file mode 100644 index 0000000000..6c3965107b --- /dev/null +++ b/src/prototype/DynamicsArchitecture/Base.py @@ -0,0 +1,13 @@ + + +class Base: + def __init__(self): + # States + self.sigma_BN = None + self.omega_BN = None + self.omegaDot_BN = None + + # Storage + self.r_BN = None + self.rDot_BN = None + self.rDDot_BN = None diff --git a/src/prototype/DynamicsArchitecture/Categorizer.py b/src/prototype/DynamicsArchitecture/Categorizer.py new file mode 100644 index 0000000000..943a63906a --- /dev/null +++ b/src/prototype/DynamicsArchitecture/Categorizer.py @@ -0,0 +1,168 @@ +import math + + +class Node: + def __init__(self, tag): + self.tag = tag + self.adjacentNodeList = [] + self.visited = False + + def __str__(self): + string = "Node " + self.tag + " has connections " + for nodeInfo in self.adjacentNodeList: + string = string + " " + nodeInfo[0].tag + f"-{nodeInfo[1]}" + return string + + +def addEdge(node1, node2, weight): + node1.adjacentNodeList.append([node2, weight]) + node2.adjacentNodeList.append([node1, weight]) + + +def findBase(nodeList): + for node in nodeList: + node.visited = False + + for node in nodeList: + print("### Checking node " + node.tag + " ###") + if checkBase(node): + for nodeNew in nodeList: + nodeNew.visited = False + return node + for nodeNew in nodeList: + nodeNew.visited = False + + +def checkBase(node): + node.visited = True + for adjNodeInfo in node.adjacentNodeList: + result = adjNodeInfo[1] + search(adjNodeInfo, node) + if result > 3: + print("Error: found a long chain") + return False + if math.isnan(result): + return False + return True + + +def search(nodeInfo, parentNode): + print(nodeInfo[0].tag) + nodeInfo[0].visited = True + + numConnections = len(nodeInfo[0].adjacentNodeList) + if numConnections > 2: + print("ERROR: found a fork") + return math.nan + elif numConnections == 1: + return 0 + + for adjNodeInfo in nodeInfo[0].adjacentNodeList: + if adjNodeInfo[0].tag == parentNode.tag: + continue + if adjNodeInfo[0].visited: + print("ERROR: found a loop") + return math.nan + + return adjNodeInfo[1] + search(adjNodeInfo, nodeInfo[0]) + + +def fork(): + # Make the following graph + # A + # / \ + # 1 1 + # / \ + # D B + # / \ \ + # 2 1 1 + # / \ \ + # G E C + # \ + # 1 + # \ + # F + nodeList = [Node("A"), Node("B"), Node("C"), Node("D"), Node("E"), Node("F"), Node("G")] + addEdge(nodeList[0], nodeList[1], 1) + addEdge(nodeList[1], nodeList[2], 1) + addEdge(nodeList[0], nodeList[3], 1) + addEdge(nodeList[3], nodeList[4], 1) + addEdge(nodeList[4], nodeList[5], 1) + addEdge(nodeList[3], nodeList[6], 2) + + print("### Graph structure ###") + for node in nodeList: + print(node) + + return nodeList + + +def longChain(): + # Make the following graph + # A + # \ + # 2 + # \ + # B + # \ + # 1 + # \ + # C + # \ + # 2 + # \ + # D + nodeList = [Node("A"), Node("B"), Node("C"), Node("D")] + addEdge(nodeList[0], nodeList[1], 2) + addEdge(nodeList[1], nodeList[2], 1) + addEdge(nodeList[2], nodeList[3], 2) + + print("### Graph structure ###") + for node in nodeList: + print(node) + + return nodeList + + +def loop(): + # Make the following graph + # A - 1 - B + # | | + # 1 1 + # | | + # C - 1 - D + # \ + # 1 + # \ + # E + nodeList = [Node("A"), Node("B"), Node("C"), Node("D"), Node("E")] + addEdge(nodeList[0], nodeList[1], 1) + addEdge(nodeList[0], nodeList[2], 1) + addEdge(nodeList[1], nodeList[3], 1) + addEdge(nodeList[2], nodeList[3], 1) + addEdge(nodeList[3], nodeList[4], 1) + + print("### Graph structure ###") + for node in nodeList: + print(node) + + return nodeList + + +def Graph(tag): + if tag == "fork": + return fork() + elif tag == "longChain": + return longChain() + elif tag == "loop": + return loop() + + +if __name__ == "__main__": + # Choose the graph to analyze + graph = Graph("fork") # fork, longChain, loop + + baseNode = findBase(graph) + if baseNode is None: + print("### No Base node found ###") + else: + print("### Base node is " + baseNode.tag + " ###") diff --git a/src/prototype/DynamicsArchitecture/DynamicsEngine.py b/src/prototype/DynamicsArchitecture/DynamicsEngine.py new file mode 100644 index 0000000000..7b9fbe6dff --- /dev/null +++ b/src/prototype/DynamicsArchitecture/DynamicsEngine.py @@ -0,0 +1,18 @@ +class DynamicsEngine: + def __init__(self): + self.systemList = [] + + def categorizeSystem(self): + return + + def propagateStates(self): + # NEED TO FIGURE OUT SYSTEM INTERACTION + + # Loop through all systems + for system in self.systemList: + system.propagateDynamics() + + # where to update kinematics? + + def setEnvironment(self): + return diff --git a/src/prototype/DynamicsArchitecture/External Disturbance.py b/src/prototype/DynamicsArchitecture/External Disturbance.py new file mode 100644 index 0000000000..d0065d1258 --- /dev/null +++ b/src/prototype/DynamicsArchitecture/External Disturbance.py @@ -0,0 +1,5 @@ + +class ExternalDisturbance: + def __init__(self): + self.force = None + self.torque = None diff --git a/src/prototype/DynamicsArchitecture/Subsystem.py b/src/prototype/DynamicsArchitecture/Subsystem.py new file mode 100644 index 0000000000..2feb5e0c60 --- /dev/null +++ b/src/prototype/DynamicsArchitecture/Subsystem.py @@ -0,0 +1,21 @@ + + +class Subsystem: + def __init__(self): + self.states = None + + self.a = None + self.b = None + self.c = None + + def updateEffectorMassProps(self): + return + + def updateContributions(self): + return + + def updateEnergyMomContributions(self): + return + + def computeDerivatives(self): + return diff --git a/src/prototype/DynamicsArchitecture/System.py b/src/prototype/DynamicsArchitecture/System.py new file mode 100644 index 0000000000..d3e2d41722 --- /dev/null +++ b/src/prototype/DynamicsArchitecture/System.py @@ -0,0 +1,18 @@ +class System: + def __init__(self): + self.massSC = None + self.ISC = None + self.r_CN = None + self.rDot_CN = None + self.r_CN = None + self.rDot_CB = None + + self.base = None + self.subsytemList = [] + + def propagateDynamics(self): + for subsystem in self.subsytemList: + subsystem.updateEffectorMassProps() + subsystem.computeDerivatives() + subsystem.updateContributions() + subsystem.updateEnergyMomContributions() diff --git a/src/prototype/KinematicsArchitecture/Assembly.py b/src/prototype/KinematicsArchitecture/Assembly.py new file mode 100644 index 0000000000..fb7cc37e24 --- /dev/null +++ b/src/prototype/KinematicsArchitecture/Assembly.py @@ -0,0 +1,9 @@ + +class Assembly: + def __init__(self): + self.initialFrame = None + self.finalFrame = None + + def makeAssembly(self, partList, jointList): + return + diff --git a/src/prototype/KinematicsArchitecture/AttitudeParameterization.py b/src/prototype/KinematicsArchitecture/AttitudeParameterization.py new file mode 100644 index 0000000000..db8f523474 --- /dev/null +++ b/src/prototype/KinematicsArchitecture/AttitudeParameterization.py @@ -0,0 +1,48 @@ +from utilities import RigidBodyKinematics as rbk + +class DCM: + def __init__(self, dcm): + self.dcm = dcm + + def toMRP(self): + return MRP(rbk.C2MRP(self.dcm)) + + +class Euler321: + def __init__(self, euler): + self.euler = euler + + def toMRP(self): + return MRP(rbk.euler3212MRP(self.euler)) + + +class PRV: + def __init__(self, prv): + self.prv = prv + + def toMRP(self): + return MRP(rbk.PRV2MRP(self.prv)) + + +class Quaternion: + def __init__(self, quaternion): + self.quaternion = quaternion + + def toMRP(self): + return MRP(rbk.EP2MRP(self.quaternion)) + + +class CRP: + def __init__(self, crp): + self.crp = crp + + def toMRP(self): + return MRP(rbk.gibbs2MRP(self.crp)) + + +class MRP: + def __init__(self, mrp): + self.mrp = mrp + + def toMRP(self): + return self diff --git a/src/prototype/KinematicsArchitecture/Frame.py b/src/prototype/KinematicsArchitecture/Frame.py new file mode 100644 index 0000000000..e681135018 --- /dev/null +++ b/src/prototype/KinematicsArchitecture/Frame.py @@ -0,0 +1,21 @@ +from prototype.KinematicsArchitecture.KinematicsEngine import * +from prototype.KinematicsArchitecture.Vector import Vector +from prototype.KinematicsArchitecture.AttitudeParameterization import MRP + + +class Frame: + def __init__(self, attitude_SP, omega_SP_S, omegaDot_SP_S, r_SP_P, rDot_SP_P, rDDot_SP_P, parentFrame): + # Create non-initialized fields + self.parentFrame = parentFrame + # self.inertial = self.parentFrame.parentFrame is None + + # Initialize variables from constructor + self.r_SP_P = Vector(r_SP_P, self.parentFrame) + self.rDot_SP_P = Vector(rDot_SP_P, self.parentFrame) + self.rDDot_SP_P = Vector(rDDot_SP_P, self.parentFrame) + self.sigma_SP = attitude_SP.toMRP() + self.omega_SP_S = Vector(omega_SP_S, self) + self.omegaDot_SP_S = Vector(omegaDot_SP_S, self) + + def addParentFrame(self, parentFrame): + self.parentFrame = parentFrame diff --git a/src/prototype/KinematicsArchitecture/Graph.py b/src/prototype/KinematicsArchitecture/Graph.py new file mode 100644 index 0000000000..02ddfd72a7 --- /dev/null +++ b/src/prototype/KinematicsArchitecture/Graph.py @@ -0,0 +1,95 @@ +class Graph: + def __init__(self): + return + + +class Node: + def __init__(self, parentNode, frame): + self.childrenNodeList = [] + self.parentNode = parentNode + if parentNode is not None: + self.parentNode.childrenNodeList.append(self) + + self.frame = frame + + +# Helper function to find the LCA +def findLCA(path1, path2): + ind = 0 + # Now iterate over the path list found. + while ind < len(path1) and ind < len(path2): + # If there is a mismatch break the loop. + if path1[ind] != path2[ind]: + break + ind += 1 + + # Return the node encountered just before + # the mismatch. + return path1[ind-1:], path2[ind-1:] + + +def findPath(node, frame, path): + path.append(node.frame) + + if node.frame == frame: + return True + + for childNode in node.childrenNodeList: + if findPath(childNode, frame, path): + return True + + path.pop() + + # Returning false if nothing worked out. + return False + + +def findPathAlternate(frame, path): + newFrame = frame + while newFrame is not None: + path.append(newFrame) + newFrame = newFrame.parentFrame + + path.reverse() + + +if __name__ == "__main__": + # Making the following tree + # 1 + # /|\ + # / | \ + # 2 3 4 + # / \ \ + # / \ \ + # 5 6 7 + # /|\ + # / | \ + # 8 9 10 + node1 = Node(None, 1) + node2 = Node(node1, 2) + node3 = Node(node1, 3) + node4 = Node(node1, 4) + node5 = Node(node2, 5) + node6 = Node(node2, 6) + node7 = Node(node4, 7) + node8 = Node(node6, 8) + node9 = Node(node6, 9) + node10 = Node(node6, 10) + + # Choose the nodes + frame1 = 5 + frame2 = 8 + + # Find the path + path1 = [] + path2 = [] + findPath(node1, frame1, path1) + findPath(node1, frame2, path2) + print(f'Path from node {frame1} to base node: {path1}') + print(f'Path from node {frame2} to base node: {path2}') + + # Find the common ancestor between two frames and return path to it + path2LCA1, path2LCA2 = findLCA(path1, path2) + print(f'Paths to least common ancestor between node {frame1} and {frame2}:') + print(path2LCA1) + print(path2LCA2) diff --git a/src/prototype/KinematicsArchitecture/Hinge.py b/src/prototype/KinematicsArchitecture/Hinge.py new file mode 100644 index 0000000000..20db350b7c --- /dev/null +++ b/src/prototype/KinematicsArchitecture/Hinge.py @@ -0,0 +1,34 @@ +from prototype.KinematicsArchitecture.KinematicsEngine import * +from prototype.KinematicsArchitecture.Frame import Frame +from prototype.KinematicsArchitecture.AttitudeParameterization import PRV +import numpy as np + + +class Hinge: + # Initialize the class variables + def __init__(self, kinematicsEngine, equilibriumFrame, spinAxis, thetaInit, thetaDotInit, k, c): + # Initialize variables from constructor + self.equilibriumFrame = equilibriumFrame + self.spinAxis = spinAxis + self.theta = thetaInit + self.thetaDot = thetaDotInit + self.k = k + self.c = c + self.actuator = None + + # Set the current frame + # WE NEED TO ADD THIS TO THE LIST OF FRAMES + self.currentFrame = Frame(PRV(self.theta * self.spinAxis), self.thetaDot * self.spinAxis, np.array([0, 0, 0]), + np.array([0, 0, 0]), np.array([0, 0, 0]), np.array([0, 0, 0]), self.equilibriumFrame) + kinematicsEngine.frameList.append(self.currentFrame) + + def updateKinematicsStates(self, theta, thetaDot): + self.theta = theta + self.thetaDot = thetaDot + + def updateFrameStates(self): + self.currentFrame.sigma_CP = PRV(self.theta * self.spinAxis).toMRP() + self.currentFrame.omega_CP_C = self.thetaDot * self.spinAxis + + def connectActuator(self, actuator): + self.actuator = actuator diff --git a/src/prototype/KinematicsArchitecture/Joint.py b/src/prototype/KinematicsArchitecture/Joint.py new file mode 100644 index 0000000000..3286f29e60 --- /dev/null +++ b/src/prototype/KinematicsArchitecture/Joint.py @@ -0,0 +1,25 @@ +from prototype.KinematicsArchitecture.Hinge import Hinge + + +class Joint: + def __init__(self): + self.lowerFrame = None + self.upperFrame = None + + def connectPartToLowerConnectionPoint(self, part): + self.lowerFrame.addParentFrame(part.frame) + + def connectPartToUpperConnectionPoint(self, part): + part.frame.addParentFrame(self.upperFrame) + + +class Joint1D(Joint): + def __init__(self, kinematicsEngine, equilibriumFrame, spinAxis, thetaInit, thetaDotInit, k, c): + super().__init__() + + # Create the frame + self.hinge = Hinge(kinematicsEngine, equilibriumFrame, spinAxis, thetaInit, thetaDotInit, k, c) + + # Populate lower and upper frames + self.lowerFrame = self.hinge.equilibriumFrame + self.upperFrame = self.hinge.currentFrame diff --git a/src/prototype/KinematicsArchitecture/KinematicsEngine.py b/src/prototype/KinematicsArchitecture/KinematicsEngine.py new file mode 100644 index 0000000000..3642c62dbf --- /dev/null +++ b/src/prototype/KinematicsArchitecture/KinematicsEngine.py @@ -0,0 +1,110 @@ +from prototype.KinematicsArchitecture.Frame import Frame +from prototype.KinematicsArchitecture.Part import Part +from prototype.KinematicsArchitecture.AttitudeParameterization import MRP +from prototype.KinematicsArchitecture.Joint import Joint1D +from prototype.KinematicsArchitecture.Hinge import Hinge +from prototype.KinematicsArchitecture.Graph import findPathAlternate, findLCA + + +class KinematicsEngine: + def __init__(self): + self.frameList = [] + self.partList = [] + self.jointList = [] + self.assemblyList = [] + + self.rootFrame = Frame(MRP([0, 0, 0]), [0, 0, 0], [0, 0, 0], [0, 0, 0], [0, 0, 0], [0, 0, 0], None) + self.frameList.append(self.rootFrame) + + def createFrame(self, attitude_SP=MRP([0, 0, 0]), omega_SP_S=None, omegaDot_SP_S=None, + r_SP_P=None, rDot_SP_P=None, rDDot_SP_P=None, parentFrame=None): + # Default parameter handling + if r_SP_P is None: + r_SP_P = [0, 0, 0] + if rDot_SP_P is None: + rDot_SP_P = [0, 0, 0] + if rDDot_SP_P is None: + rDDot_SP_P = [0, 0, 0] + if omega_SP_S is None: + omega_SP_S = [0, 0, 0] + if omegaDot_SP_S is None: + omegaDot_SP_S = [0, 0, 0] + if parentFrame is None: + parentFrame = self.rootFrame + + # Create the frame + frame = Frame(attitude_SP, omega_SP_S, omegaDot_SP_S, r_SP_P, rDot_SP_P, rDDot_SP_P, parentFrame) + self.frameList.append(frame) + + return frame + + def createPart(self, attitude_SP=None, omega_SP_S=None, omegaDot_SP_S=None, + r_SP_P=None, rDot_SP_P=None, rDDot_SP_P=None, parentFrame=None, + r_ScP_P=None, m=0, I=None): + # Default parameter handling + if attitude_SP is None: + attitude_SP = MRP([0, 0, 0]) + if omega_SP_S is None: + omega_SP_S = [0, 0, 0] + if omegaDot_SP_S is None: + omegaDot_SP_S = [0, 0, 0] + if r_SP_P is None: + r_SP_P = [0, 0, 0] + if rDot_SP_P is None: + rDot_SP_P = [0, 0, 0] + if rDDot_SP_P is None: + rDDot_SP_P = [0, 0, 0] + if parentFrame is None: + parentFrame = self.createFrame() + if I is None: + I = [[0, 0, 0], [0, 0, 0], [0, 0, 0]] + + # Create the frame and part + frame = self.createFrame(attitude_SP, omega_SP_S, omegaDot_SP_S, r_SP_P, rDot_SP_P, rDDot_SP_P, parentFrame) + part = Part(r_ScP_P, frame, m, I) + self.partList.append(part) + + return part + + def createJoint1D(self, spinAxis, equilibriumFrame=None, thetaInit=0, thetaDotInit=0, k=0, c=0): + if equilibriumFrame is None: + equilibriumFrame = self.createFrame() + + # Create the joint + joint = Joint1D(self, equilibriumFrame, spinAxis, thetaInit, thetaDotInit, k, c) + self.jointList.append(joint) + + return joint + + def connect2Upper(self, part, joint): + part.frame.addParentFrame(joint.upperFrame) + + def connect2Lower(self, part, joint): + joint.lowerFrame.addParentFrame(part.frame) + + def relativeKinematics(self, frame1, frame2): + # Find the absolute path for the frames of the two parts + path1 = [] + path2 = [] + findPathAlternate(frame1, path1) + findPathAlternate(frame2, path2) + + # Find the path to the least common ancestor for both part frames + pathToLCA1, pathToLCA2 = findLCA(path1, path2) + + # Loop through each path and calculate the relative kinematics + + # Return the result + return Frame(MRP([0, 0, 0]), [0, 0, 0], [0, 0, 0], [0, 0, 0], [0, 0, 0], [0, 0, 0], None) + + def vectorTransportTheorem(self): + return + + def inertiaTransportTheorem(self): + return + + def attitudeKinematics(self): + return + + def updateKinematics(self): + return diff --git a/src/prototype/KinematicsArchitecture/Part.py b/src/prototype/KinematicsArchitecture/Part.py new file mode 100644 index 0000000000..961f5548fc --- /dev/null +++ b/src/prototype/KinematicsArchitecture/Part.py @@ -0,0 +1,13 @@ +from prototype.KinematicsArchitecture.KinematicsEngine import * +from prototype.KinematicsArchitecture.Frame import Frame +from prototype.KinematicsArchitecture.Vector import Vector, Tensor + + +class Part: + def __init__(self, r_ScP_P, frame, m, I): + # Update the frame + self.frame = frame + + self.m = m + self.I = Tensor(I, self.frame) + self.r_ScP_P = Vector(r_ScP_P, self.frame.parentFrame) diff --git a/src/prototype/KinematicsArchitecture/Vector.py b/src/prototype/KinematicsArchitecture/Vector.py new file mode 100644 index 0000000000..49eb562ef1 --- /dev/null +++ b/src/prototype/KinematicsArchitecture/Vector.py @@ -0,0 +1,13 @@ +from prototype.KinematicsArchitecture.KinematicsEngine import * + + +class Vector: + def __init__(self, vectorArray, frame): + self.vectorArray = vectorArray + self.frame = frame + + +class Tensor: + def __init__(self, tensorArray, frame): + self.tensorArray = tensorArray + self.frame = frame diff --git a/src/prototype/Space Vehicle.py b/src/prototype/Space Vehicle.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/src/prototype/scenarios/scenarioDynamics.py b/src/prototype/scenarios/scenarioDynamics.py new file mode 100644 index 0000000000..2247c6782c --- /dev/null +++ b/src/prototype/scenarios/scenarioDynamics.py @@ -0,0 +1 @@ +import numpy as np \ No newline at end of file diff --git a/src/prototype/scenarios/scenarioKinematics.py b/src/prototype/scenarios/scenarioKinematics.py new file mode 100644 index 0000000000..843764289c --- /dev/null +++ b/src/prototype/scenarios/scenarioKinematics.py @@ -0,0 +1,34 @@ +import numpy as np + +from prototype.KinematicsArchitecture.KinematicsEngine import KinematicsEngine +from prototype.KinematicsArchitecture.AttitudeParameterization import Quaternion + + +def run(): + # Create the kinematics engine + myKinematicsEngine = KinematicsEngine() + + # Define the inertial frame + inertialFrame = myKinematicsEngine.createFrame() + + # Define parts + beta = Quaternion([0, 0, 1, 0]) + myPart1 = myKinematicsEngine.createPart(attitude_SP=beta, parentFrame=inertialFrame) + myPart2 = myKinematicsEngine.createPart() + myPart3 = myKinematicsEngine.createPart(parentFrame=inertialFrame) + + # Define a 1D joint + spinAxis = np.array([1, 0, 0]) + myJoint = myKinematicsEngine.createJoint1D(spinAxis) + + # Connect the parts with the joint + myKinematicsEngine.connect2Lower(myPart1, myJoint) + myKinematicsEngine.connect2Upper(myPart2, myJoint) + + relativeFrame = myKinematicsEngine.relativeKinematics(myPart2.frame, myPart3.frame) + + breakpoint() + + +if __name__ == "__main__": + run()