File: main.py

package info (click to toggle)
dart 6.12.1%2Bdfsg4-12
  • links: PTS, VCS
  • area: main
  • in suites: bookworm
  • size: 57,000 kB
  • sloc: cpp: 269,461; python: 3,911; xml: 1,273; sh: 404; makefile: 30
file content (69 lines) | stat: -rw-r--r-- 1,963 bytes parent folder | download | duplicates (2)
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
import math
import numpy as np
import dartpy as dart


class MyWorldNode(dart.gui.osg.RealTimeWorldNode):
    def __init__(self, world, chain):
        super(MyWorldNode, self).__init__(world)
        self.chain = chain

    def customPreStep(self):
        pass


def main():
    world = dart.utils.SkelParser.readWorld('dart://sample/skel/chain.skel');
    world.setGravity([0, -9.81, 0])
    world.setTimeStep(1.0/2000)

    chain = world.getSkeleton(0)
    for i in range(chain.getNumJoints()):
        joint = chain.getJoint(i)
        for j in range(joint.getNumDofs()):
            joint.setDampingCoefficient(j, 0.01)

    dof = chain.getNumDofs()

    init_pose = np.zeros(dof)
    init_pose[20] = math.pi * 0.4
    init_pose[23] = math.pi * 0.4
    init_pose[26] = math.pi * 0.4
    init_pose[29] = math.pi * 0.4
    chain.setPositions(init_pose)

    # Create a ball joint contraint
    bd1 = chain.getBodyNode('link 6')
    bd2 = chain.getBodyNode('link 10')
    shape_node1 = bd1.getShapeNode(0)
    shape_node2 = bd2.getShapeNode(0)
    visual1 = shape_node1.getVisualAspect()
    visual2 = shape_node2.getVisualAspect()
    visual1.setColor([1, 0, 0])
    visual2.setColor([1, 0, 0])

    offset = [0, 0.025, 0]
    joint_pos = bd1.getTransform().multiply(offset)
    constraint = dart.constraint.BallJointConstraint(bd1, bd2, joint_pos)
    constraint_solver = world.getConstraintSolver()
    constraint_solver.addConstraint(constraint)

    node = MyWorldNode(world, chain)

    # Create world node and add it to viewer
    viewer = dart.gui.osg.Viewer()
    viewer.addWorldNode(node)

    # Grid settings
    grid = dart.gui.osg.GridVisual()
    grid.setPlaneType(dart.gui.osg.GridVisual.PlaneType.ZX)
    grid.setOffset([0, -0.55, 0])
    viewer.addAttachment(grid)

    viewer.setUpViewInWindow(0, 0, 640, 480)
    viewer.setCameraHomePosition([0.6, 0.3, 0.6], [0, -0.2, 0], [0, 1, 0])
    viewer.run()


if __name__ == "__main__":
    main()