-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathgenerate.py
More file actions
76 lines (57 loc) · 1.8 KB
/
generate.py
File metadata and controls
76 lines (57 loc) · 1.8 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
import random
import pyrosim.pyrosim as pyrosim
def Create_World():
pyrosim.Start_SDF('world.sdf')
pyrosim.Send_Cube(
name="Box",
pos=[-2, 2, .5],
size=[1, 1, 1]
)
pyrosim.End()
def Create_Robot():
pyrosim.Start_URDF("body.urdf")
pyrosim.Send_Cube(
name="LinkTorso",
pos=[0, 0, 1.5],
size=[1, 1, 1]
)
pyrosim.Send_Joint(
name="LinkTorso_LinkBackLeg",
parent="LinkTorso",
child="LinkBackLeg",
type="revolute",
position=[-.5, 0, 1]
)
pyrosim.Send_Cube(
name="LinkBackLeg",
pos=[-.5, 0, -.5],
size=[1, 1, 1]
)
pyrosim.Send_Joint(
name="LinkTorso_LinkFrontLeg",
parent="LinkTorso",
child="LinkFrontLeg",
type="revolute",
position=[.5, 0, 1]
)
pyrosim.Send_Cube(
name="LinkFrontLeg",
pos=[.5, 0, -.5],
size=[1, 1, 1]
)
pyrosim.End()
def Create_Brain():
pyrosim.Start_NeuralNetwork('brain.nndf')
pyrosim.Send_Sensor_Neuron(name=0, linkName='LinkTorso')
pyrosim.Send_Sensor_Neuron(name=1, linkName='LinkBackLeg')
pyrosim.Send_Sensor_Neuron(name=2, linkName='LinkFrontLeg')
pyrosim.Send_Motor_Neuron(name=3, jointName='LinkTorso_LinkBackLeg')
pyrosim.Send_Motor_Neuron(name=4, jointName='LinkTorso_LinkFrontLeg')
for i in range(3):
for j in range(2):
pyrosim.Send_Synapse(sourceNeuronName=i, targetNeuronName=j+3, weight=random.random() * 2 - 1)
pyrosim.End()
if __name__ == '__main__':
Create_World()
Create_Robot()
Create_Brain()