This repository was archived by the owner on Sep 23, 2022. It is now read-only.
forked from DAInamite/programming-humanoid-robot-in-python
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathagent_server.py
More file actions
81 lines (67 loc) · 2.56 KB
/
agent_server.py
File metadata and controls
81 lines (67 loc) · 2.56 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
77
78
79
80
'''In this file you need to implement remote procedure call (RPC) server
* There are different RPC libraries for python, such as xmlrpclib, json-rpc. You are free to choose.
* The following functions have to be implemented and exported:
* get_angle
* set_angle
* get_posture
* execute_keyframes
* get_transform
* set_transform
* You can test RPC server with ipython before implementing agent_client.py
'''
# add PYTHONPATH
import os
import sys
sys.path.append(os.path.join(os.path.abspath(os.path.dirname(__file__)), '..', 'kinematics'))
from inverse_kinematics import InverseKinematicsAgent
import time
import xmlrpc.server
import threading
import numpy as np
class ServerAgent(InverseKinematicsAgent):
'''ServerAgent provides RPC service
'''
def __init__(self, *args, **kwargs):
super(ServerAgent, self).__init__(*args, **kwargs)
t = threading.Thread(target=self.handle_rpcs)
t.daemon = True
t.start()
def handle_rpcs(self):
with xmlrpc.server.SimpleXMLRPCServer(("localhost", 8000), allow_none=True) as server:
server.register_function(self.get_angle)
server.register_function(self.set_angle)
server.register_function(self.get_posture)
server.register_function(self.execute_keyframes)
server.register_function(self.get_transform)
server.register_function(self.set_transform)
server.serve_forever()
def get_angle(self, joint_name):
'''get sensor value of given joint'''
return self.sensor_joints[joint_name]
def set_angle(self, joint_name, angle):
'''set target angle of joint for PID controller
'''
self.target_joints[joint_name] = angle
def get_posture(self):
'''return current posture of robot'''
return self.posture
def execute_keyframes(self, keyframes):
'''excute keyframes, note this function is blocking call,
e.g. return until keyframes are executed
'''
while len(self.keyframes[0]) > 0:
time.sleep(1/100)
self.keyframes = keyframes
while len(self.keyframes[0]) > 0:
time.sleep(1/100)
def get_transform(self, name):
'''get transform with given name
'''
return self.transforms[name].tolist()
def set_transform(self, effector_name, transform):
'''solve the inverse kinematics and control joints use the results
'''
self.set_transforms(effector_name, np.array(transform, np.float32))
if __name__ == '__main__':
agent = ServerAgent()
agent.run()