├── vision ├── image077.png └── getting_images.ipynb ├── introduction ├── nao_camera.png ├── README.md ├── set_joint_commands.py ├── get_sensor_data.py └── naoqi_basic.ipynb ├── joint_control ├── robot_pose_image │ ├── Sit.png │ ├── Back.png │ ├── Belly.png │ ├── Left.png │ ├── Right.png │ ├── Stand.png │ ├── Crouch.png │ ├── HeadBack.png │ └── StandInit.png ├── keyframes │ ├── __init__.py │ ├── hello.py │ └── wipe_forehead.py ├── recognize_posture.py ├── robot_pose_data_json │ ├── Knee │ ├── Frog │ ├── HeadBack │ ├── Right │ ├── Stand │ ├── Belly │ ├── Back │ ├── Left │ ├── Sit │ ├── Crouch │ └── StandInit ├── standing_up.py ├── README.md ├── angle_interpolation.py ├── robot_pose_data │ ├── Knee │ ├── Frog │ ├── HeadBack │ ├── Belly │ ├── Right │ ├── Stand │ ├── Back │ ├── Left │ ├── Sit │ ├── Crouch │ └── StandInit ├── pid.py └── learn_posture.ipynb ├── distributed_computing ├── README.md ├── agent_server.py └── agent_client.py ├── kinematics ├── README.md ├── inverse_kinematics.py ├── fk_samples.json └── forward_kinematics.py ├── .gitignore ├── README.md ├── software_installation ├── README.md ├── sexpr.py ├── spark_agent.py ├── numpy_baisc.ipynb └── python_basic.ipynb └── nao_doc └── vision.rst /vision/image077.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DAInamite/programming-humanoid-robot-in-python/HEAD/vision/image077.png -------------------------------------------------------------------------------- /introduction/nao_camera.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DAInamite/programming-humanoid-robot-in-python/HEAD/introduction/nao_camera.png -------------------------------------------------------------------------------- /joint_control/robot_pose_image/Sit.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DAInamite/programming-humanoid-robot-in-python/HEAD/joint_control/robot_pose_image/Sit.png -------------------------------------------------------------------------------- /joint_control/robot_pose_image/Back.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DAInamite/programming-humanoid-robot-in-python/HEAD/joint_control/robot_pose_image/Back.png -------------------------------------------------------------------------------- /joint_control/robot_pose_image/Belly.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DAInamite/programming-humanoid-robot-in-python/HEAD/joint_control/robot_pose_image/Belly.png -------------------------------------------------------------------------------- /joint_control/robot_pose_image/Left.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DAInamite/programming-humanoid-robot-in-python/HEAD/joint_control/robot_pose_image/Left.png -------------------------------------------------------------------------------- /joint_control/robot_pose_image/Right.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DAInamite/programming-humanoid-robot-in-python/HEAD/joint_control/robot_pose_image/Right.png -------------------------------------------------------------------------------- /joint_control/robot_pose_image/Stand.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DAInamite/programming-humanoid-robot-in-python/HEAD/joint_control/robot_pose_image/Stand.png -------------------------------------------------------------------------------- /joint_control/robot_pose_image/Crouch.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DAInamite/programming-humanoid-robot-in-python/HEAD/joint_control/robot_pose_image/Crouch.png -------------------------------------------------------------------------------- /joint_control/robot_pose_image/HeadBack.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DAInamite/programming-humanoid-robot-in-python/HEAD/joint_control/robot_pose_image/HeadBack.png -------------------------------------------------------------------------------- /joint_control/robot_pose_image/StandInit.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DAInamite/programming-humanoid-robot-in-python/HEAD/joint_control/robot_pose_image/StandInit.png -------------------------------------------------------------------------------- /joint_control/keyframes/__init__.py: -------------------------------------------------------------------------------- 1 | '''Keyframes from Aldebaran 2 | ''' 3 | 4 | from .leftBackToStand import leftBackToStand 5 | from .leftBellyToStand import leftBellyToStand 6 | from .rightBackToStand import rightBackToStand 7 | from .rightBellyToStand import rightBellyToStand 8 | 9 | from .hello import hello 10 | from .wipe_forehead import wipe_forehead 11 | -------------------------------------------------------------------------------- /distributed_computing/README.md: -------------------------------------------------------------------------------- 1 | # 5: Distributed Computing 2 | This week you need to implement distributed computing via [remote procedure call (RPC)](https://en.wikipedia.org/wiki/Remote_procedure_call), which has similiar interface you get with real robot via PyNaoQi. 3 | 4 | The server and client have to be implemented together: 5 | * [ServerAgent](./agent_server.py) provides remote RPC service; 6 | * [ClientAgent](./agent_client.py) requests remote call from server and provides non-blocking capibility. 7 | 8 | 9 | -------------------------------------------------------------------------------- /introduction/README.md: -------------------------------------------------------------------------------- 1 | # 2: Introduction and Sample Agent 2 | 3 | Please follow [software installation](../software_installation/README.md) first, and then complete the exercise. 4 | 5 | ## Programming exercise 6 | Open the following python files, write code following comments in files. 7 | 8 | * [get_sensor_data.py](./get_sensor_data.py) 9 | * [set_joint_commands.py](./set_joint_commands.py) 10 | 11 | For testing, start simspark first, and execute python file, e.g. ```python get_sensor_data.py``` 12 | 13 | 14 | -------------------------------------------------------------------------------- /kinematics/README.md: -------------------------------------------------------------------------------- 1 | # 4: Kinematics 2 | This week you need to implement forward and inverse kinematics for NAO robot, and test in simulation. You may first take a look at [2D forward and inverse kinematics](robot_arm_2d.ipynb) with ipython notebook, then complete the code in [forward_kinematics.py](./forward_kinematics.py) and [inverse_kinematics.py](./inverse_kinematics.py). 3 | 4 | The documentation of NAO can be found here: http://doc.aldebaran.com/2-1/family/nao_h25/index_h25.html#nao-h25 5 | 6 | An analytical solution for NAO's leg is described in section 8.3.4 [B-Human Team Report and Code Release 2017](https://github.com/bhuman/BHumanCodeRelease/blob/coderelease2017/CodeRelease2017.pdf) 7 | 8 | 9 | 10 | -------------------------------------------------------------------------------- /introduction/set_joint_commands.py: -------------------------------------------------------------------------------- 1 | ''' 2 | In this exercise you need to know how to set joint commands. 3 | 4 | * Tasks: 5 | 1. set stiffness of LShoulderPitch to 0 6 | 2. set speed of HeadYaw to 0.1 7 | 8 | * Hint: The commands are stored in action (class Action in spark_agent.py) 9 | 10 | ''' 11 | 12 | # add PYTHONPATH 13 | import os 14 | import sys 15 | sys.path.append(os.path.join(os.path.abspath(os.path.dirname(__file__)), '..', 'software_installation')) 16 | 17 | from spark_agent import SparkAgent 18 | 19 | 20 | class MyAgent(SparkAgent): 21 | def think(self, perception): 22 | action = super(MyAgent, self).think(perception) 23 | # YOUR CODE HERE 24 | 25 | return action 26 | 27 | if '__main__' == __name__: 28 | agent = MyAgent() 29 | agent.run() 30 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | # Byte-compiled / optimized / DLL files 2 | __pycache__/ 3 | *.py[cod] 4 | 5 | # C extensions 6 | *.so 7 | 8 | # Distribution / packaging 9 | .Python 10 | env/ 11 | build/ 12 | develop-eggs/ 13 | dist/ 14 | downloads/ 15 | eggs/ 16 | lib/ 17 | lib64/ 18 | parts/ 19 | sdist/ 20 | var/ 21 | *.egg-info/ 22 | .installed.cfg 23 | *.egg 24 | 25 | # PyInstaller 26 | # Usually these files are written by a python script from a template 27 | # before PyInstaller builds the exe, so as to inject date/other infos into it. 28 | *.manifest 29 | *.spec 30 | 31 | # Installer logs 32 | pip-log.txt 33 | pip-delete-this-directory.txt 34 | 35 | # Unit test / coverage reports 36 | htmlcov/ 37 | .tox/ 38 | .coverage 39 | .cache 40 | nosetests.xml 41 | coverage.xml 42 | 43 | # Translations 44 | *.mo 45 | *.pot 46 | 47 | # Django stuff: 48 | *.log 49 | 50 | # Sphinx documentation 51 | docs/_build/ 52 | 53 | # PyBuilder 54 | target/ 55 | .ipynb_checkpoints 56 | -------------------------------------------------------------------------------- /introduction/get_sensor_data.py: -------------------------------------------------------------------------------- 1 | ''' 2 | In this exercise you need to know how to get sensor data. 3 | 4 | * Task: get the current joint angle and temperature of joint HeadYaw 5 | 6 | * Hint: The current sensor data of robot is stored in perception (class Perception in spark_agent.py) 7 | 8 | ''' 9 | 10 | # add PYTHONPATH 11 | import os 12 | import sys 13 | sys.path.append(os.path.join(os.path.abspath(os.path.dirname(__file__)), '..', 'software_installation')) 14 | 15 | from spark_agent import SparkAgent 16 | 17 | 18 | class MyAgent(SparkAgent): 19 | def think(self, perception): 20 | angle = 0 21 | temperature = 0 22 | # YOUR CODE HERE 23 | # get angle and temperature to current data of joint HeadYaw 24 | 25 | print('HeadYaw angle: ' + str(angle) + ' temperature: ' + str(temperature)) 26 | return super(MyAgent, self).think(perception) 27 | 28 | if '__main__' == __name__: 29 | agent = MyAgent() 30 | agent.run() 31 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | Programming Humanoid Robot In Python 2 | ==================================== 3 | 4 | Source code for [Programming Humanoid Robot in Python](http://www.dainamite.de/#program_soccer_robots) Lecture in TU Berlin. 5 | 6 | 1. [Software Installtion](./software_installation) 7 | 2. [Introduction](./introduction) 8 | 3. [Joint Control](./joint_control) 9 | 4. [Kinematics](./kinematics) 10 | 5. [Distributed Computing](./distributed_computing) 11 | 12 | ## How to submit your exercise? 13 | ### inital setup 14 | * create a github account if you don't have 15 | * open [repository page](https://github.com/DAInamite/programming-humanoid-robot-in-python) 16 | * click "Fork" button in top right corner 17 | * clone your fork to your computer: 18 | ```sh 19 | git clone git@github.com:YOUR_GITHUB_ACCOUNT/programming-humanoid-robot-in-python.git 20 | ``` 21 | 22 | ### update in following weeks 23 | This repo is work in progress, please [sync git](https://help.github.com/articles/syncing-a-fork/) before doing exercise every week. 24 | 25 | ### program and submit 26 | 27 | * do exercises 28 | * commit your code and push to github 29 | * submit your **git repo url** via ISIS assignment page 30 | 31 | ## Demo in lecture 32 | The demo showed in lecture are included in this repo as well, please check files (mostly *.ipynb) in subfolders. 33 | -------------------------------------------------------------------------------- /joint_control/recognize_posture.py: -------------------------------------------------------------------------------- 1 | '''In this exercise you need to use the learned classifier to recognize current posture of robot 2 | 3 | * Tasks: 4 | 1. load learned classifier in `PostureRecognitionAgent.__init__` 5 | 2. recognize current posture in `PostureRecognitionAgent.recognize_posture` 6 | 7 | * Hints: 8 | Let the robot execute different keyframes, and recognize these postures. 9 | 10 | ''' 11 | 12 | 13 | from angle_interpolation import AngleInterpolationAgent 14 | from keyframes import hello 15 | 16 | 17 | class PostureRecognitionAgent(AngleInterpolationAgent): 18 | def __init__(self, simspark_ip='localhost', 19 | simspark_port=3100, 20 | teamname='DAInamite', 21 | player_id=0, 22 | sync_mode=True): 23 | super(PostureRecognitionAgent, self).__init__(simspark_ip, simspark_port, teamname, player_id, sync_mode) 24 | self.posture = 'unknown' 25 | self.posture_classifier = None # LOAD YOUR CLASSIFIER 26 | 27 | def think(self, perception): 28 | self.posture = self.recognize_posture(perception) 29 | return super(PostureRecognitionAgent, self).think(perception) 30 | 31 | def recognize_posture(self, perception): 32 | posture = 'unknown' 33 | # YOUR CODE HERE 34 | 35 | return posture 36 | 37 | if __name__ == '__main__': 38 | agent = PostureRecognitionAgent() 39 | agent.keyframes = hello() # CHANGE DIFFERENT KEYFRAMES 40 | agent.run() 41 | -------------------------------------------------------------------------------- /kinematics/inverse_kinematics.py: -------------------------------------------------------------------------------- 1 | '''In this exercise you need to implement inverse kinematics for NAO's legs 2 | 3 | * Tasks: 4 | 1. solve inverse kinematics for NAO's legs by using analytical or numerical method. 5 | You may need documentation of NAO's leg: 6 | http://doc.aldebaran.com/2-1/family/nao_h21/joints_h21.html 7 | http://doc.aldebaran.com/2-1/family/nao_h21/links_h21.html 8 | 2. use the results of inverse kinematics to control NAO's legs (in InverseKinematicsAgent.set_transforms) 9 | and test your inverse kinematics implementation. 10 | ''' 11 | 12 | 13 | from forward_kinematics import ForwardKinematicsAgent 14 | from numpy.matlib import identity 15 | 16 | 17 | class InverseKinematicsAgent(ForwardKinematicsAgent): 18 | def inverse_kinematics(self, effector_name, transform): 19 | '''solve the inverse kinematics 20 | 21 | :param str effector_name: name of end effector, e.g. LLeg, RLeg 22 | :param transform: 4x4 transform matrix 23 | :return: list of joint angles 24 | ''' 25 | joint_angles = [] 26 | # YOUR CODE HERE 27 | return joint_angles 28 | 29 | def set_transforms(self, effector_name, transform): 30 | '''solve the inverse kinematics and control joints use the results 31 | ''' 32 | # YOUR CODE HERE 33 | self.keyframes = ([], [], []) # the result joint angles have to fill in 34 | 35 | if __name__ == '__main__': 36 | agent = InverseKinematicsAgent() 37 | # test inverse kinematics 38 | T = identity(4) 39 | T[-1, 1] = 0.05 40 | T[-1, 2] = -0.26 41 | agent.set_transforms('LLeg', T) 42 | agent.run() 43 | -------------------------------------------------------------------------------- /distributed_computing/agent_server.py: -------------------------------------------------------------------------------- 1 | '''In this file you need to implement remote procedure call (RPC) server 2 | 3 | * There are different RPC libraries for python, such as xmlrpclib, json-rpc. You are free to choose. 4 | * The following functions have to be implemented and exported: 5 | * get_angle 6 | * set_angle 7 | * get_posture 8 | * execute_keyframes 9 | * get_transform 10 | * set_transform 11 | * You can test RPC server with ipython before implementing agent_client.py 12 | ''' 13 | 14 | # add PYTHONPATH 15 | import os 16 | import sys 17 | sys.path.append(os.path.join(os.path.abspath(os.path.dirname(__file__)), '..', 'kinematics')) 18 | 19 | from inverse_kinematics import InverseKinematicsAgent 20 | 21 | 22 | class ServerAgent(InverseKinematicsAgent): 23 | '''ServerAgent provides RPC service 24 | ''' 25 | # YOUR CODE HERE 26 | 27 | def get_angle(self, joint_name): 28 | '''get sensor value of given joint''' 29 | # YOUR CODE HERE 30 | 31 | def set_angle(self, joint_name, angle): 32 | '''set target angle of joint for PID controller 33 | ''' 34 | # YOUR CODE HERE 35 | 36 | def get_posture(self): 37 | '''return current posture of robot''' 38 | # YOUR CODE HERE 39 | 40 | def execute_keyframes(self, keyframes): 41 | '''excute keyframes, note this function is blocking call, 42 | e.g. return until keyframes are executed 43 | ''' 44 | # YOUR CODE HERE 45 | 46 | def get_transform(self, name): 47 | '''get transform with given name 48 | ''' 49 | # YOUR CODE HERE 50 | 51 | def set_transform(self, effector_name, transform): 52 | '''solve the inverse kinematics and control joints use the results 53 | ''' 54 | # YOUR CODE HERE 55 | 56 | if __name__ == '__main__': 57 | agent = ServerAgent() 58 | agent.run() 59 | 60 | -------------------------------------------------------------------------------- /joint_control/robot_pose_data_json/Knee: -------------------------------------------------------------------------------- 1 | [[0.3037738800048828, 0.015382050536572933, 0.42035794258117676, 1.9818861484527588, 0.3037738800048828, -0.01683211326599121, 0.5199840068817139, 1.7119860649108887, 0.0, -0.08726692199707031], [0.3037738800048828, 0.015382050536572933, 0.42035794258117676, 1.9818861484527588, 0.3037738800048828, -0.01683211326599121, 0.5199840068817139, 1.7119860649108887, 0.0, -0.08726692199707031], [0.3037738800048828, 0.013848066329956055, 0.42035794258117676, 1.9818861484527588, 0.3037738800048828, -0.01683211326599121, 0.5199840068817139, 1.7119860649108887, 0.0, -0.08726692199707031], [0.3037738800048828, 0.015382050536572933, 0.42035794258117676, 1.9818861484527588, 0.3037738800048828, -0.01683211326599121, 0.5199840068817139, 1.7119860649108887, 0.0, -0.08726692199707031], [0.3037738800048828, 0.015382050536572933, 0.42035794258117676, 1.9818861484527588, 0.3037738800048828, -0.01683211326599121, 0.5199840068817139, 1.7119860649108887, 0.0, -0.08726692199707031], [0.3037738800048828, 0.015382050536572933, 0.42035794258117676, 1.9818861484527588, 0.3037738800048828, -0.01683211326599121, 0.5199840068817139, 1.7119860649108887, 0.0, -0.08726692199707031], [0.3037738800048828, 0.015382050536572933, 0.42035794258117676, 1.9818861484527588, 0.3037738800048828, -0.01683211326599121, 0.5199840068817139, 1.7119860649108887, 0.0, -0.08726692199707031], [0.3037738800048828, 0.015382050536572933, 0.42035794258117676, 1.9818861484527588, 0.3037738800048828, -0.01683211326599121, 0.5199840068817139, 1.7119860649108887, 0.0, -0.08726692199707031], [0.3037738800048828, 0.015382050536572933, 0.42035794258117676, 1.9818861484527588, 0.3037738800048828, -0.01683211326599121, 0.5199840068817139, 1.7119860649108887, 0.0, -0.08726692199707031], [0.3037738800048828, 0.015382050536572933, 0.42035794258117676, 1.9818861484527588, 0.3037738800048828, -0.01683211326599121, 0.5199840068817139, 1.7119860649108887, 0.0, -0.08726692199707031]] -------------------------------------------------------------------------------- /joint_control/standing_up.py: -------------------------------------------------------------------------------- 1 | '''In this exercise you need to put all code together to make the robot be able to stand up by its own. 2 | 3 | * Task: 4 | complete the `StandingUpAgent.standing_up` function, e.g. call keyframe motion corresponds to current posture 5 | 6 | ''' 7 | 8 | 9 | from recognize_posture import PostureRecognitionAgent 10 | 11 | 12 | class StandingUpAgent(PostureRecognitionAgent): 13 | def think(self, perception): 14 | self.standing_up() 15 | return super(StandingUpAgent, self).think(perception) 16 | 17 | def standing_up(self): 18 | posture = self.posture 19 | # YOUR CODE HERE 20 | 21 | 22 | class TestStandingUpAgent(StandingUpAgent): 23 | '''this agent turns off all motor to falls down in fixed cycles 24 | ''' 25 | def __init__(self, simspark_ip='localhost', 26 | simspark_port=3100, 27 | teamname='DAInamite', 28 | player_id=0, 29 | sync_mode=True): 30 | super(TestStandingUpAgent, self).__init__(simspark_ip, simspark_port, teamname, player_id, sync_mode) 31 | self.stiffness_on_off_time = 0 32 | self.stiffness_on_cycle = 10 # in seconds 33 | self.stiffness_off_cycle = 3 # in seconds 34 | 35 | def think(self, perception): 36 | action = super(TestStandingUpAgent, self).think(perception) 37 | time_now = perception.time 38 | if time_now - self.stiffness_on_off_time < self.stiffness_off_cycle: 39 | action.stiffness = {j: 0 for j in self.joint_names} # turn off joints 40 | else: 41 | action.stiffness = {j: 1 for j in self.joint_names} # turn on joints 42 | if time_now - self.stiffness_on_off_time > self.stiffness_on_cycle + self.stiffness_off_cycle: 43 | self.stiffness_on_off_time = time_now 44 | 45 | return action 46 | 47 | 48 | if __name__ == '__main__': 49 | agent = TestStandingUpAgent() 50 | agent.run() 51 | -------------------------------------------------------------------------------- /joint_control/robot_pose_data_json/Frog: -------------------------------------------------------------------------------- 1 | [[-0.40953612327575684, -0.19477605819702148, -1.579978108406067, 2.136820077896118, -0.40953612327575684, 0.2853660583496094, -1.6613640785217285, 2.13997220993042, -0.02792501449584961, 0.9896016120910645], [-0.40953612327575684, -0.19631004333496094, -1.5815120935440063, 2.136820077896118, -0.40953612327575684, 0.2853660583496094, -1.6613640785217285, 2.13997220993042, -0.03490638732910156, 0.9913468360900879], [-0.40953612327575684, -0.19477605819702148, -1.5815120935440063, 2.136820077896118, -0.40953612327575684, 0.2853660583496094, -1.6613640785217285, 2.13997220993042, -0.03490638732910156, 0.9948372840881348], [-0.40953612327575684, -0.19477605819702148, -1.579978108406067, 2.136820077896118, -0.40953612327575684, 0.2853660583496094, -1.6613640785217285, 2.13997220993042, -0.033161163330078125, 0.9948372840881348], [-0.40953612327575684, -0.19477605819702148, -1.579978108406067, 2.136820077896118, -0.40953612327575684, 0.2853660583496094, -1.662898063659668, 2.13997220993042, -0.033161163330078125, 0.9843654632568359], [-0.40953612327575684, -0.19631004333496094, -1.579978108406067, 2.136820077896118, -0.40953612327575684, 0.2853660583496094, -1.6613640785217285, 2.13997220993042, -0.033161163330078125, 0.9843654632568359], [-0.40953612327575684, -0.19477605819702148, -1.579978108406067, 2.136820077896118, -0.40953612327575684, 0.2853660583496094, -1.6613640785217285, 2.13997220993042, -0.033161163330078125, 0.9843654632568359], [-0.40953612327575684, -0.19477605819702148, -1.579978108406067, 2.136820077896118, -0.40953612327575684, 0.2853660583496094, -1.6613640785217285, 2.13997220993042, -0.033161163330078125, 0.9843654632568359], [-0.40953612327575684, -0.19631004333496094, -1.579978108406067, 2.136820077896118, -0.40953612327575684, 0.2853660583496094, -1.6613640785217285, 2.13997220993042, -0.033161163330078125, 0.9843654632568359], [-0.40953612327575684, -0.19477605819702148, -1.579978108406067, 2.136820077896118, -0.40953612327575684, 0.2853660583496094, -1.6613640785217285, 2.13997220993042, -0.033161163330078125, 0.9861106872558594]] -------------------------------------------------------------------------------- /joint_control/robot_pose_data_json/HeadBack: -------------------------------------------------------------------------------- 1 | [[0.2055978775024414, -0.23926210403442383, -0.2438640594482422, -0.03072190284729004, 0.2055978775024414, -0.13955211639404297, -4.1961669921875e-05, -0.13341593742370605, -3.054325580596924, -0.02094411849975586], [0.2055978775024414, -0.23926210403442383, -0.2438640594482422, -0.03072190284729004, 0.2055978775024414, -0.13955211639404297, -4.1961669921875e-05, -0.13341593742370605, -3.054325580596924, -0.02094411849975586], [0.2055978775024414, -0.23926210403442383, -0.2438640594482422, -0.03072190284729004, 0.2055978775024414, -0.13955211639404297, -4.1961669921875e-05, -0.13341593742370605, -3.054325580596924, -0.02094411849975586], [0.2055978775024414, -0.23926210403442383, -0.2438640594482422, -0.03072190284729004, 0.2055978775024414, -0.13955211639404297, -4.1961669921875e-05, -0.13341593742370605, -3.0525803565979004, -0.02094411849975586], [0.2055978775024414, -0.24079608917236328, -0.2438640594482422, -0.03072190284729004, 0.2055978775024414, -0.13955211639404297, -4.1961669921875e-05, -0.13341593742370605, -3.0525803565979004, -0.02094411849975586], [0.2055978775024414, -0.24079608917236328, -0.2438640594482422, -0.03072190284729004, 0.2055978775024414, -0.13955211639404297, -4.1961669921875e-05, -0.13341593742370605, -3.054325580596924, -0.02094411849975586], [0.2055978775024414, -0.23926210403442383, -0.2438640594482422, -0.03072190284729004, 0.2055978775024414, -0.13955211639404297, -4.1961669921875e-05, -0.13341593742370605, -3.054325580596924, -0.02094411849975586], [0.2055978775024414, -0.24079608917236328, -0.2438640594482422, -0.03072190284729004, 0.2055978775024414, -0.13955211639404297, -4.1961669921875e-05, -0.13341593742370605, -3.0525803565979004, -0.02094411849975586], [0.2055978775024414, -0.24079608917236328, -0.2438640594482422, -0.03072190284729004, 0.2055978775024414, -0.13955211639404297, -4.1961669921875e-05, -0.13341593742370605, -3.0525803565979004, -0.02094411849975586], [0.2055978775024414, -0.24079608917236328, -0.2438640594482422, -0.03072190284729004, 0.2055978775024414, -0.13955211639404297, -4.1961669921875e-05, -0.13341593742370605, -3.0525803565979004, -0.02094411849975586]] -------------------------------------------------------------------------------- /introduction/naoqi_basic.ipynb: -------------------------------------------------------------------------------- 1 | { 2 | "metadata": { 3 | "name": "" 4 | }, 5 | "nbformat": 3, 6 | "nbformat_minor": 0, 7 | "worksheets": [ 8 | { 9 | "cells": [ 10 | { 11 | "cell_type": "heading", 12 | "level": 1, 13 | "metadata": {}, 14 | "source": [ 15 | "NAOqi Basic" 16 | ] 17 | }, 18 | { 19 | "cell_type": "code", 20 | "collapsed": false, 21 | "input": [ 22 | "from naoqi import ALProxy" 23 | ], 24 | "language": "python", 25 | "metadata": {}, 26 | "outputs": [], 27 | "prompt_number": 1 28 | }, 29 | { 30 | "cell_type": "code", 31 | "collapsed": false, 32 | "input": [ 33 | "tts = ALProxy('ALTextToSpeech', 'nao6.local', 9559)" 34 | ], 35 | "language": "python", 36 | "metadata": {}, 37 | "outputs": [], 38 | "prompt_number": 2 39 | }, 40 | { 41 | "cell_type": "code", 42 | "collapsed": false, 43 | "input": [ 44 | "tts.say('Hi, I am here. Have you enjoy?')" 45 | ], 46 | "language": "python", 47 | "metadata": {}, 48 | "outputs": [], 49 | "prompt_number": 4 50 | }, 51 | { 52 | "cell_type": "code", 53 | "collapsed": false, 54 | "input": [ 55 | "motion = ALProxy('ALMotion', 'nao6.local', 9559)" 56 | ], 57 | "language": "python", 58 | "metadata": {}, 59 | "outputs": [], 60 | "prompt_number": 5 61 | }, 62 | { 63 | "cell_type": "code", 64 | "collapsed": false, 65 | "input": [ 66 | "motion.wakeUp()" 67 | ], 68 | "language": "python", 69 | "metadata": {}, 70 | "outputs": [], 71 | "prompt_number": 6 72 | }, 73 | { 74 | "cell_type": "code", 75 | "collapsed": false, 76 | "input": [ 77 | "motion.rest()" 78 | ], 79 | "language": "python", 80 | "metadata": {}, 81 | "outputs": [], 82 | "prompt_number": 7 83 | }, 84 | { 85 | "cell_type": "code", 86 | "collapsed": false, 87 | "input": [], 88 | "language": "python", 89 | "metadata": {}, 90 | "outputs": [] 91 | } 92 | ], 93 | "metadata": {} 94 | } 95 | ] 96 | } -------------------------------------------------------------------------------- /joint_control/robot_pose_data_json/Right: -------------------------------------------------------------------------------- 1 | [[0.10588788986206055, 0.33905601501464844, -0.49083805084228516, -0.13196587562561035, 0.10588788986206055, 0.3559298515319824, -0.6750020980834961, 0.052197933197021484, 1.3264503479003906, 0.08901166915893555], [0.10588788986206055, 0.33905601501464844, -0.49083805084228516, -0.13196587562561035, 0.10588788986206055, 0.3559298515319824, -0.6750020980834961, 0.05066394805908203, 1.3264503479003906, 0.08901166915893555], [0.10588788986206055, 0.3405900001525879, -0.49083805084228516, -0.13196587562561035, 0.10588788986206055, 0.3559298515319824, -0.6750020980834961, 0.052197933197021484, 1.3264503479003906, 0.08901166915893555], [0.10588788986206055, 0.33905601501464844, -0.49083805084228516, -0.13196587562561035, 0.10588788986206055, 0.357464075088501, -0.6734678745269775, 0.052197933197021484, 1.3159785270690918, 0.09075689315795898], [0.10588788986206055, 0.33905601501464844, -0.49083805084228516, -0.13196587562561035, 0.10588788986206055, 0.357464075088501, -0.6750020980834961, 0.052197933197021484, 1.3159785270690918, 0.09075689315795898], [0.10588788986206055, 0.3405900001525879, -0.49083805084228516, -0.13196587562561035, 0.10588788986206055, 0.3559298515319824, -0.6750020980834961, 0.052197933197021484, 1.3159785270690918, 0.09075689315795898], [0.10588788986206055, 0.33905601501464844, -0.49083805084228516, -0.13196587562561035, 0.10588788986206055, 0.3559298515319824, -0.6750020980834961, 0.052197933197021484, 1.3159785270690918, 0.09075689315795898], [0.10588788986206055, 0.3405900001525879, -0.4893040657043457, -0.13196587562561035, 0.10588788986206055, 0.3559298515319824, -0.6750020980834961, 0.052197933197021484, 1.3159785270690918, 0.09075689315795898], [0.10588788986206055, 0.33905601501464844, -0.49083805084228516, -0.13196587562561035, 0.10588788986206055, 0.3559298515319824, -0.6750020980834961, 0.052197933197021484, 1.3159785270690918, 0.08901166915893555], [0.10588788986206055, 0.33905601501464844, -0.49083805084228516, -0.13196587562561035, 0.10588788986206055, 0.3559298515319824, -0.6750020980834961, 0.052197933197021484, 1.3177237510681152, 0.08901166915893555], [-0.1579599380493164, -0.3251659870147705, -0.7562201023101807, 2.083130121231079, -0.15949392318725586, 0.10895586013793945, -1.540177822113037, 2.1353702545166016, 1.4346609115600586, 0.1099553108215332]] -------------------------------------------------------------------------------- /distributed_computing/agent_client.py: -------------------------------------------------------------------------------- 1 | '''In this file you need to implement remote procedure call (RPC) client 2 | 3 | * The agent_server.py has to be implemented first (at least one function is implemented and exported) 4 | * Please implement functions in ClientAgent first, which should request remote call directly 5 | * The PostHandler can be implement in the last step, it provides non-blocking functions, e.g. agent.post.execute_keyframes 6 | * Hints: [threading](https://docs.python.org/2/library/threading.html) may be needed for monitoring if the task is done 7 | ''' 8 | 9 | import weakref 10 | 11 | class PostHandler(object): 12 | '''the post hander wraps function to be excuted in paralle 13 | ''' 14 | def __init__(self, obj): 15 | self.proxy = weakref.proxy(obj) 16 | 17 | def execute_keyframes(self, keyframes): 18 | '''non-blocking call of ClientAgent.execute_keyframes''' 19 | # YOUR CODE HERE 20 | 21 | def set_transform(self, effector_name, transform): 22 | '''non-blocking call of ClientAgent.set_transform''' 23 | # YOUR CODE HERE 24 | 25 | 26 | class ClientAgent(object): 27 | '''ClientAgent request RPC service from remote server 28 | ''' 29 | # YOUR CODE HERE 30 | def __init__(self): 31 | self.post = PostHandler(self) 32 | 33 | def get_angle(self, joint_name): 34 | '''get sensor value of given joint''' 35 | # YOUR CODE HERE 36 | 37 | def set_angle(self, joint_name, angle): 38 | '''set target angle of joint for PID controller 39 | ''' 40 | # YOUR CODE HERE 41 | 42 | def get_posture(self): 43 | '''return current posture of robot''' 44 | # YOUR CODE HERE 45 | 46 | def execute_keyframes(self, keyframes): 47 | '''excute keyframes, note this function is blocking call, 48 | e.g. return until keyframes are executed 49 | ''' 50 | # YOUR CODE HERE 51 | 52 | def get_transform(self, name): 53 | '''get transform with given name 54 | ''' 55 | # YOUR CODE HERE 56 | 57 | def set_transform(self, effector_name, transform): 58 | '''solve the inverse kinematics and control joints use the results 59 | ''' 60 | # YOUR CODE HERE 61 | 62 | if __name__ == '__main__': 63 | agent = ClientAgent() 64 | # TEST CODE HERE 65 | 66 | 67 | -------------------------------------------------------------------------------- /joint_control/robot_pose_data_json/Stand: -------------------------------------------------------------------------------- 1 | [[-0.23926210403442383, 0.14883995056152344, 0.21173405647277832, -0.09054803848266602, -0.23926210403442383, -0.056715965270996094, 0.2118614763021469, -0.07665801048278809, -0.005560700315982103, -0.013422664254903793], [-0.23926210403442383, 0.14883995056152344, 0.21173405647277832, -0.09054803848266602, -0.23926210403442383, -0.05824995040893555, 0.21032725274562836, -0.07665801048278809, -0.005560700315982103, -0.013422664254903793], [-0.23926210403442383, 0.14883995056152344, 0.21173405647277832, -0.09054803848266602, -0.23926210403442383, -0.05824995040893555, 0.2118614763021469, -0.07665801048278809, -0.005560700315982103, -0.013422664254903793], [-0.23926210403442383, 0.14883995056152344, 0.21173405647277832, -0.09054803848266602, -0.23926210403442383, -0.05824995040893555, 0.21032725274562836, -0.07665801048278809, -0.00575238885357976, -0.013422664254903793], [-0.23926210403442383, 0.14883995056152344, 0.21173405647277832, -0.09054803848266602, -0.23926210403442383, -0.05824995040893555, 0.21032725274562836, -0.07665801048278809, -0.00575238885357976, -0.013422664254903793], [-0.23926210403442383, 0.14883995056152344, 0.21173405647277832, -0.09054803848266602, -0.23926210403442383, -0.05824995040893555, 0.2118614763021469, -0.07665801048278809, -0.00575238885357976, -0.013422664254903793], [-0.23926210403442383, 0.14883995056152344, 0.21173405647277832, -0.09054803848266602, -0.23926210403442383, -0.056715965270996094, 0.2118614763021469, -0.07665801048278809, -0.00575238885357976, -0.013422664254903793], [-0.23926210403442383, 0.14730596542358398, 0.21173405647277832, -0.09054803848266602, -0.23926210403442383, -0.05824995040893555, 0.2118614763021469, -0.07665801048278809, -0.005944077391177416, -0.013422664254903793], [-0.23926210403442383, 0.14883995056152344, 0.21173405647277832, -0.09054803848266602, -0.23926210403442383, -0.056715965270996094, 0.2118614763021469, -0.07665801048278809, -0.006135765928775072, -0.011696990579366684], [-0.24079608917236328, 0.14883995056152344, 0.21173405647277832, -0.09054803848266602, -0.23926210403442383, -0.056715965270996094, 0.2118614763021469, -0.07665801048278809, -0.007669751066714525, -0.015531715005636215], [-0.23926210403442383, 0.0583338737487793, 0.21173405647277832, -0.07980990409851074, -0.23926210403442383, -0.1487560272216797, 0.2118614763021469, -0.08893013000488281, 0.010546383447945118, -0.017257388681173325]] -------------------------------------------------------------------------------- /joint_control/README.md: -------------------------------------------------------------------------------- 1 | # 3: Joint Control 2 | ## PID Controller for Joint Servo 3 | 1. complete the implementation of PID controller in [pid.py](./pid.py) 4 | 2. use [pid_test.ipynb](./pid_test.ipynb) to tuning PID parameters 5 | * start ```jupyter notebook``` in this folder, then you can launch [pid_test.ipynb](./pid_test.ipynb) in your web browser 6 | * follow instruction in notebook, run the code and tune PID parameters 7 | 3. save the best parameters in ```__init__``` of ```class PIDController``` 8 | 9 | ## Keyframe Motion 10 | 1. implement angle interploation method by using splins interpolation or Bezier interpolation in file [angle_interpolation.py](./angle_interpolation.py), please follow instruction in the comments of the file. 11 | * run simspark and [angle_interpolation.py](./angle_interpolation.py) to test [hello](./keyframes/hello.py) motion 12 | 2. test your implementation with provided keyframes in [keyframes](./keyframes) folder, for example: 13 | * import keyframe with ```from keyframes import hello``` 14 | * and set the keyframe in ```main``` function, e.g. ```agent.keyframes = hello()``` 15 | * Note: the provided keyframes doesn't have joint `RHipYawPitch`, please set `RHipYawPitch` as `LHipYawPitch` which reflects the real robot. 16 | 3. (optional) create your own keyframes 17 | 18 | ## Posture Recognition 19 | use machine learning to recognize robot's posture [learn_posture.ipynb](./learn_posture.ipynb), the [scikit-learn-intro.ipynb](./scikit-learn-intro.ipynb) is a good example to follow. 20 | 21 | 1. preparing dataset (step 1~2 in [learn_posture.ipynb](./learn_posture.ipynb) ) 22 | 2. traning dataset, and save the results (step 3~5 in [learn_posture.ipynb](./learn_posture.ipynb) ) 23 | 3. getting feature data from simulation and recognize current posture in [recognize_posture.py](./recognize_posture.py) 24 | 4. if the result is not good in simulation, adding new train data with [add_training_data.ipynb](add_training_data.ipynb) 25 | 5. commit file *robot_pose.pkl* as trained result to git before submission. 26 | 27 | ### Automonous standing up 28 | 1. complete the [standing_up.py](./standing_up.py), e.g. call keyframe motion corresponds to current posture 29 | 2. Test with the ```TestStandingUpAgent``` which turns off all joints regularly to make the robot falls 30 | 3. (optional) The ```TestStandingUpAgent``` always falls to belly, please also test other suitations: e.g. execute a keyframe motion to make robot falls to another pose and let it stands up. 31 | -------------------------------------------------------------------------------- /joint_control/angle_interpolation.py: -------------------------------------------------------------------------------- 1 | '''In this exercise you need to implement an angle interploation function which makes NAO executes keyframe motion 2 | 3 | * Tasks: 4 | 1. complete the code in `AngleInterpolationAgent.angle_interpolation`, 5 | you are free to use splines interploation or Bezier interploation, 6 | but the keyframes provided are for Bezier curves, you can simply ignore some data for splines interploation, 7 | please refer data format below for details. 8 | 2. try different keyframes from `keyframes` folder 9 | 10 | * Keyframe data format: 11 | keyframe := (names, times, keys) 12 | names := [str, ...] # list of joint names 13 | times := [[float, float, ...], [float, float, ...], ...] 14 | # times is a matrix of floats: Each line corresponding to a joint, and column element to a key. 15 | keys := [[float, [int, float, float], [int, float, float]], ...] 16 | # keys is a list of angles in radians or an array of arrays each containing [float angle, Handle1, Handle2], 17 | # where Handle is [int InterpolationType, float dTime, float dAngle] describing the handle offsets relative 18 | # to the angle and time of the point. The first Bezier param describes the handle that controls the curve 19 | # preceding the point, the second describes the curve following the point. 20 | ''' 21 | 22 | 23 | from pid import PIDAgent 24 | from keyframes import hello 25 | 26 | 27 | class AngleInterpolationAgent(PIDAgent): 28 | def __init__(self, simspark_ip='localhost', 29 | simspark_port=3100, 30 | teamname='DAInamite', 31 | player_id=0, 32 | sync_mode=True): 33 | super(AngleInterpolationAgent, self).__init__(simspark_ip, simspark_port, teamname, player_id, sync_mode) 34 | self.keyframes = ([], [], []) 35 | 36 | def think(self, perception): 37 | target_joints = self.angle_interpolation(self.keyframes, perception) 38 | target_joints['RHipYawPitch'] = target_joints['LHipYawPitch'] # copy missing joint in keyframes 39 | self.target_joints.update(target_joints) 40 | return super(AngleInterpolationAgent, self).think(perception) 41 | 42 | def angle_interpolation(self, keyframes, perception): 43 | target_joints = {} 44 | # YOUR CODE HERE 45 | 46 | return target_joints 47 | 48 | if __name__ == '__main__': 49 | agent = AngleInterpolationAgent() 50 | agent.keyframes = hello() # CHANGE DIFFERENT KEYFRAMES 51 | agent.run() 52 | -------------------------------------------------------------------------------- /joint_control/robot_pose_data_json/Belly: -------------------------------------------------------------------------------- 1 | [[0.06600403785705566, 0.0061779022216796875, 0.07980990409851074, 2.0079641342163086, 0.06600403785705566, 0.0844118595123291, 0.09506607055664062, 1.8976001739501953, -0.018579784780740738, 1.4904650449752808], [0.06600403785705566, 0.007711887359619141, 0.07827591896057129, 2.0079641342163086, 0.06600403785705566, 0.08594608306884766, 0.09353208541870117, 1.8976001739501953, -0.018579784780740738, 1.490273356437683], [0.06600403785705566, 0.0061779022216796875, 0.07827591896057129, 2.0079641342163086, 0.06600403785705566, 0.08594608306884766, 0.09506607055664062, 1.8960661888122559, -0.018579784780740738, 1.490273356437683], [0.06600403785705566, 0.007711887359619141, 0.07827591896057129, 2.009498119354248, 0.06600403785705566, 0.0844118595123291, 0.09506607055664062, 1.8976001739501953, -0.018771473318338394, 1.4900816679000854], [0.06600403785705566, 0.0061779022216796875, 0.07827591896057129, 2.0079641342163086, 0.06600403785705566, 0.0844118595123291, 0.09506607055664062, 1.8960661888122559, -0.018771473318338394, 1.4864386320114136], [0.06600403785705566, 0.0061779022216796875, 0.07980990409851074, 2.0079641342163086, 0.06600403785705566, 0.08594608306884766, 0.09506607055664062, 1.8960661888122559, -0.018579784780740738, 1.4864386320114136], [0.06600403785705566, 0.0061779022216796875, 0.07827591896057129, 2.0079641342163086, 0.06600403785705566, 0.08594608306884766, 0.09353208541870117, 1.8976001739501953, -0.018579784780740738, 1.4868220090866089], [0.06600403785705566, 0.0061779022216796875, 0.07827591896057129, 2.0079641342163086, 0.06600403785705566, 0.08594608306884766, 0.09353208541870117, 1.8960661888122559, -0.02068883553147316, 1.4862464666366577], [0.06600403785705566, 0.007711887359619141, 0.07827591896057129, 2.0079641342163086, 0.06600403785705566, 0.0844118595123291, 0.09353208541870117, 1.8976001739501953, -0.01973039284348488, 1.4801105260849], [0.06600403785705566, 0.0061779022216796875, 0.07827591896057129, 2.009498119354248, 0.06600403785705566, 0.0844118595123291, 0.09506607055664062, 1.8960661888122559, -0.01973039284348488, 1.4801105260849], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.5707963267948966], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.5707963267948966], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.5707963267948966], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.5707963267948966], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.5707963267948966], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.5707963267948966], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.5707963267948966], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.5707963267948966], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.5707963267948966]] -------------------------------------------------------------------------------- /joint_control/robot_pose_data/Knee: -------------------------------------------------------------------------------- 1 | (lp0 2 | (lp1 3 | F0.3037738800048828 4 | aF0.015382050536572933 5 | aF0.42035794258117676 6 | aF1.9818861484527588 7 | aF0.3037738800048828 8 | aF-0.01683211326599121 9 | aF0.5199840068817139 10 | aF1.7119860649108887 11 | aF0.0 12 | aF-0.08726692199707031 13 | aa(lp2 14 | F0.3037738800048828 15 | aF0.015382050536572933 16 | aF0.42035794258117676 17 | aF1.9818861484527588 18 | aF0.3037738800048828 19 | aF-0.01683211326599121 20 | aF0.5199840068817139 21 | aF1.7119860649108887 22 | aF0.0 23 | aF-0.08726692199707031 24 | aa(lp3 25 | F0.3037738800048828 26 | aF0.013848066329956055 27 | aF0.42035794258117676 28 | aF1.9818861484527588 29 | aF0.3037738800048828 30 | aF-0.01683211326599121 31 | aF0.5199840068817139 32 | aF1.7119860649108887 33 | aF0.0 34 | aF-0.08726692199707031 35 | aa(lp4 36 | F0.3037738800048828 37 | aF0.015382050536572933 38 | aF0.42035794258117676 39 | aF1.9818861484527588 40 | aF0.3037738800048828 41 | aF-0.01683211326599121 42 | aF0.5199840068817139 43 | aF1.7119860649108887 44 | aF0.0 45 | aF-0.08726692199707031 46 | aa(lp5 47 | F0.3037738800048828 48 | aF0.015382050536572933 49 | aF0.42035794258117676 50 | aF1.9818861484527588 51 | aF0.3037738800048828 52 | aF-0.01683211326599121 53 | aF0.5199840068817139 54 | aF1.7119860649108887 55 | aF0.0 56 | aF-0.08726692199707031 57 | aa(lp6 58 | F0.3037738800048828 59 | aF0.015382050536572933 60 | aF0.42035794258117676 61 | aF1.9818861484527588 62 | aF0.3037738800048828 63 | aF-0.01683211326599121 64 | aF0.5199840068817139 65 | aF1.7119860649108887 66 | aF0.0 67 | aF-0.08726692199707031 68 | aa(lp7 69 | F0.3037738800048828 70 | aF0.015382050536572933 71 | aF0.42035794258117676 72 | aF1.9818861484527588 73 | aF0.3037738800048828 74 | aF-0.01683211326599121 75 | aF0.5199840068817139 76 | aF1.7119860649108887 77 | aF0.0 78 | aF-0.08726692199707031 79 | aa(lp8 80 | F0.3037738800048828 81 | aF0.015382050536572933 82 | aF0.42035794258117676 83 | aF1.9818861484527588 84 | aF0.3037738800048828 85 | aF-0.01683211326599121 86 | aF0.5199840068817139 87 | aF1.7119860649108887 88 | aF0.0 89 | aF-0.08726692199707031 90 | aa(lp9 91 | F0.3037738800048828 92 | aF0.015382050536572933 93 | aF0.42035794258117676 94 | aF1.9818861484527588 95 | aF0.3037738800048828 96 | aF-0.01683211326599121 97 | aF0.5199840068817139 98 | aF1.7119860649108887 99 | aF0.0 100 | aF-0.08726692199707031 101 | aa(lp10 102 | F0.3037738800048828 103 | aF0.015382050536572933 104 | aF0.42035794258117676 105 | aF1.9818861484527588 106 | aF0.3037738800048828 107 | aF-0.01683211326599121 108 | aF0.5199840068817139 109 | aF1.7119860649108887 110 | aF0.0 111 | aF-0.08726692199707031 112 | aa. -------------------------------------------------------------------------------- /joint_control/robot_pose_data/Frog: -------------------------------------------------------------------------------- 1 | (lp0 2 | (lp1 3 | F-0.40953612327575684 4 | aF-0.19477605819702148 5 | aF-1.579978108406067 6 | aF2.136820077896118 7 | aF-0.40953612327575684 8 | aF0.2853660583496094 9 | aF-1.6613640785217285 10 | aF2.13997220993042 11 | aF-0.02792501449584961 12 | aF0.9896016120910645 13 | aa(lp2 14 | F-0.40953612327575684 15 | aF-0.19631004333496094 16 | aF-1.5815120935440063 17 | aF2.136820077896118 18 | aF-0.40953612327575684 19 | aF0.2853660583496094 20 | aF-1.6613640785217285 21 | aF2.13997220993042 22 | aF-0.03490638732910156 23 | aF0.9913468360900879 24 | aa(lp3 25 | F-0.40953612327575684 26 | aF-0.19477605819702148 27 | aF-1.5815120935440063 28 | aF2.136820077896118 29 | aF-0.40953612327575684 30 | aF0.2853660583496094 31 | aF-1.6613640785217285 32 | aF2.13997220993042 33 | aF-0.03490638732910156 34 | aF0.9948372840881348 35 | aa(lp4 36 | F-0.40953612327575684 37 | aF-0.19477605819702148 38 | aF-1.579978108406067 39 | aF2.136820077896118 40 | aF-0.40953612327575684 41 | aF0.2853660583496094 42 | aF-1.6613640785217285 43 | aF2.13997220993042 44 | aF-0.033161163330078125 45 | aF0.9948372840881348 46 | aa(lp5 47 | F-0.40953612327575684 48 | aF-0.19477605819702148 49 | aF-1.579978108406067 50 | aF2.136820077896118 51 | aF-0.40953612327575684 52 | aF0.2853660583496094 53 | aF-1.662898063659668 54 | aF2.13997220993042 55 | aF-0.033161163330078125 56 | aF0.9843654632568359 57 | aa(lp6 58 | F-0.40953612327575684 59 | aF-0.19631004333496094 60 | aF-1.579978108406067 61 | aF2.136820077896118 62 | aF-0.40953612327575684 63 | aF0.2853660583496094 64 | aF-1.6613640785217285 65 | aF2.13997220993042 66 | aF-0.033161163330078125 67 | aF0.9843654632568359 68 | aa(lp7 69 | F-0.40953612327575684 70 | aF-0.19477605819702148 71 | aF-1.579978108406067 72 | aF2.136820077896118 73 | aF-0.40953612327575684 74 | aF0.2853660583496094 75 | aF-1.6613640785217285 76 | aF2.13997220993042 77 | aF-0.033161163330078125 78 | aF0.9843654632568359 79 | aa(lp8 80 | F-0.40953612327575684 81 | aF-0.19477605819702148 82 | aF-1.579978108406067 83 | aF2.136820077896118 84 | aF-0.40953612327575684 85 | aF0.2853660583496094 86 | aF-1.6613640785217285 87 | aF2.13997220993042 88 | aF-0.033161163330078125 89 | aF0.9843654632568359 90 | aa(lp9 91 | F-0.40953612327575684 92 | aF-0.19631004333496094 93 | aF-1.579978108406067 94 | aF2.136820077896118 95 | aF-0.40953612327575684 96 | aF0.2853660583496094 97 | aF-1.6613640785217285 98 | aF2.13997220993042 99 | aF-0.033161163330078125 100 | aF0.9843654632568359 101 | aa(lp10 102 | F-0.40953612327575684 103 | aF-0.19477605819702148 104 | aF-1.579978108406067 105 | aF2.136820077896118 106 | aF-0.40953612327575684 107 | aF0.2853660583496094 108 | aF-1.6613640785217285 109 | aF2.13997220993042 110 | aF-0.033161163330078125 111 | aF0.9861106872558594 112 | aa. -------------------------------------------------------------------------------- /kinematics/fk_samples.json: -------------------------------------------------------------------------------- 1 | {"names": ["HeadPitch", "LElbowRoll", "RElbowRoll", "LAnkleRoll", "RAnkleRoll"], "moveInit": {"positions": [[0.0, 0.0, 0.12650001049041748, 0.0, -0.0, 0.0], [0.0037460161838680506, 0.1396665871143341, 0.002532757818698883, 1.1555455923080444, 1.4754527807235718, 1.1572233438491821], [0.0037460161838680506, -0.1396665871143341, 0.002532757818698883, -1.1555455923080444, 1.4754527807235718, -1.1572233438491821], [0.004297628998756409, 0.05000000074505806, -0.24286866188049316, 0.0, -0.0, 0.0], [0.004297628998756409, -0.05000000074505806, -0.24286866188049316, 0.0, -0.0, 0.0]], "angles": [-0.0, 0.0, 1.5323816537857056, 0.2618168294429779, 0.0, -0.1745329201221466, -0.0, -0.0, -0.7175921201705933, 1.3576916456222534, -0.6400995254516602, -0.0, -0.0, 0.0, -0.7175921201705933, 1.3576916456222534, -0.6400995254516602, 0.0, 1.5323816537857056, -0.2618168294429779, -0.0, 0.1745329201221466]}, "joint_names": ["HeadYaw", "HeadPitch", "LShoulderPitch", "LShoulderRoll", "LElbowYaw", "LElbowRoll", "LHipYawPitch", "LHipRoll", "LHipPitch", "LKneePitch", "LAnklePitch", "LAnkleRoll", "RHipYawPitch", "RHipRoll", "RHipPitch", "RKneePitch", "RAnklePitch", "RAnkleRoll", "RShoulderPitch", "RShoulderRoll", "RElbowYaw", "RElbowRoll"], "init": {"positions": [[0.0, 0.0, 0.12650001049041748, 0.0, -0.0, 0.0], [0.10486510396003723, 0.11391571909189224, 0.10000000149011612, 0.0, -0.0, 0.0], [0.10486510396003723, -0.11391571909189224, 0.10000000149011612, 0.0, -0.0, 0.0], [0.0, 0.05000000074505806, -0.28790000081062317, 0.0, -0.0, 0.0], [0.0, -0.05000000074505806, -0.28790000081062317, 0.0, -0.0, 0.0]], "angles": [-0.0, 0.0, 0.0, 0.008726646192371845, 0.0, -0.008726646192371845, -0.0, -0.0, -0.0, -0.0, -0.0, -0.0, -0.0, 0.0, -0.0, -0.0, -0.0, 0.0, 0.0, -0.008726646192371845, -0.0, 0.008726646192371845]}, "rest": {"positions": [[0.0, 0.0, 0.12650001049041748, 0.0, 0.07670722156763077, -0.018500490114092827], [0.010597468353807926, 0.12226731330156326, -0.0027073174715042114, -1.425681710243225, 0.3591214716434479, -0.8309606313705444], [-0.0006455734837800264, -0.11622143536806107, -0.004487141966819763, 1.5492147207260132, 0.3520662188529968, 0.663205623626709], [-0.014167554676532745, 0.03703329712152481, -0.19279691576957703, -0.017570311203598976, -0.01443916093558073, 0.1720438003540039], [-0.013564229011535645, -0.038498736917972565, -0.19157296419143677, -0.011409442871809006, -0.01957651786506176, -0.1809605360031128]], "angles": [-0.018500490114092827, 0.07670722156763077, 1.4679789543151855, 0.08894197642803192, -0.6841865181922913, -1.2118170261383057, -0.2637890577316284, -0.07878416031599045, -0.6887767314910889, 2.0018577575683594, -1.1412882804870605, 0.0783652812242508, -0.2722539007663727, 0.0711570754647255, -0.6965259909629822, 2.018787384033203, -1.1493691205978394, -0.09470156580209732, 1.5769747495651245, -0.030752701684832573, 0.9004851579666138, 1.2426046133041382]}} 2 | -------------------------------------------------------------------------------- /joint_control/robot_pose_data/HeadBack: -------------------------------------------------------------------------------- 1 | (lp0 2 | (lp1 3 | F0.2055978775024414 4 | aF-0.23926210403442383 5 | aF-0.2438640594482422 6 | aF-0.03072190284729004 7 | aF0.2055978775024414 8 | aF-0.13955211639404297 9 | aF-4.1961669921875e-05 10 | aF-0.13341593742370605 11 | aF-3.054325580596924 12 | aF-0.02094411849975586 13 | aa(lp2 14 | F0.2055978775024414 15 | aF-0.23926210403442383 16 | aF-0.2438640594482422 17 | aF-0.03072190284729004 18 | aF0.2055978775024414 19 | aF-0.13955211639404297 20 | aF-4.1961669921875e-05 21 | aF-0.13341593742370605 22 | aF-3.054325580596924 23 | aF-0.02094411849975586 24 | aa(lp3 25 | F0.2055978775024414 26 | aF-0.23926210403442383 27 | aF-0.2438640594482422 28 | aF-0.03072190284729004 29 | aF0.2055978775024414 30 | aF-0.13955211639404297 31 | aF-4.1961669921875e-05 32 | aF-0.13341593742370605 33 | aF-3.054325580596924 34 | aF-0.02094411849975586 35 | aa(lp4 36 | F0.2055978775024414 37 | aF-0.23926210403442383 38 | aF-0.2438640594482422 39 | aF-0.03072190284729004 40 | aF0.2055978775024414 41 | aF-0.13955211639404297 42 | aF-4.1961669921875e-05 43 | aF-0.13341593742370605 44 | aF-3.0525803565979004 45 | aF-0.02094411849975586 46 | aa(lp5 47 | F0.2055978775024414 48 | aF-0.24079608917236328 49 | aF-0.2438640594482422 50 | aF-0.03072190284729004 51 | aF0.2055978775024414 52 | aF-0.13955211639404297 53 | aF-4.1961669921875e-05 54 | aF-0.13341593742370605 55 | aF-3.0525803565979004 56 | aF-0.02094411849975586 57 | aa(lp6 58 | F0.2055978775024414 59 | aF-0.24079608917236328 60 | aF-0.2438640594482422 61 | aF-0.03072190284729004 62 | aF0.2055978775024414 63 | aF-0.13955211639404297 64 | aF-4.1961669921875e-05 65 | aF-0.13341593742370605 66 | aF-3.054325580596924 67 | aF-0.02094411849975586 68 | aa(lp7 69 | F0.2055978775024414 70 | aF-0.23926210403442383 71 | aF-0.2438640594482422 72 | aF-0.03072190284729004 73 | aF0.2055978775024414 74 | aF-0.13955211639404297 75 | aF-4.1961669921875e-05 76 | aF-0.13341593742370605 77 | aF-3.054325580596924 78 | aF-0.02094411849975586 79 | aa(lp8 80 | F0.2055978775024414 81 | aF-0.24079608917236328 82 | aF-0.2438640594482422 83 | aF-0.03072190284729004 84 | aF0.2055978775024414 85 | aF-0.13955211639404297 86 | aF-4.1961669921875e-05 87 | aF-0.13341593742370605 88 | aF-3.0525803565979004 89 | aF-0.02094411849975586 90 | aa(lp9 91 | F0.2055978775024414 92 | aF-0.24079608917236328 93 | aF-0.2438640594482422 94 | aF-0.03072190284729004 95 | aF0.2055978775024414 96 | aF-0.13955211639404297 97 | aF-4.1961669921875e-05 98 | aF-0.13341593742370605 99 | aF-3.0525803565979004 100 | aF-0.02094411849975586 101 | aa(lp10 102 | F0.2055978775024414 103 | aF-0.24079608917236328 104 | aF-0.2438640594482422 105 | aF-0.03072190284729004 106 | aF0.2055978775024414 107 | aF-0.13955211639404297 108 | aF-4.1961669921875e-05 109 | aF-0.13341593742370605 110 | aF-3.0525803565979004 111 | aF-0.02094411849975586 112 | aa. -------------------------------------------------------------------------------- /joint_control/robot_pose_data_json/Back: -------------------------------------------------------------------------------- 1 | [[-0.05058002471923828, -0.2269899845123291, -0.8298521041870117, 1.7180380821228027, -0.05058002471923828, -0.1487560272216797, -0.9311800003051758, 1.8945322036743164, -0.008992496877908707, -1.516520619392395], [-0.05058002471923828, -0.2269899845123291, -0.8298521041870117, 1.7180380821228027, -0.05058002471923828, -0.1487560272216797, -0.9311800003051758, 1.8960661888122559, -0.006883446592837572, -1.5203558206558228], [-0.05058002471923828, -0.2269899845123291, -0.8298521041870117, 1.7165040969848633, -0.05058002471923828, -0.1487560272216797, -0.9311800003051758, 1.8945322036743164, -0.006883446592837572, -1.520164132118225], [-0.05058002471923828, -0.2269899845123291, -0.8298521041870117, 1.7165040969848633, -0.05058002471923828, -0.1487560272216797, -0.9311800003051758, 1.8945322036743164, -0.007075135130435228, -1.5199724435806274], [-0.05058002471923828, -0.2269899845123291, -0.8298521041870117, 1.7165040969848633, -0.05058002471923828, -0.1487560272216797, -0.9296460151672363, 1.8945322036743164, -0.007266823668032885, -1.5199724435806274], [-0.05058002471923828, -0.2269899845123291, -0.8298521041870117, 1.7180380821228027, -0.05058002471923828, -0.1487560272216797, -0.9311800003051758, 1.8945322036743164, -0.007266823668032885, -1.5197802782058716], [-0.05058002471923828, -0.2269899845123291, -0.8298521041870117, 1.7165040969848633, -0.05058002471923828, -0.1487560272216797, -0.9311800003051758, 1.8945322036743164, -0.006883446592837572, -1.5216976404190063], [-0.05058002471923828, -0.22852396965026855, -0.8298521041870117, 1.7165040969848633, -0.05058002471923828, -0.1487560272216797, -0.9311800003051758, 1.8960661888122559, -0.008992496877908707, -1.5134526491165161], [-0.05058002471923828, -0.2269899845123291, -0.8298521041870117, 1.7165040969848633, -0.05058002471923828, -0.1487560272216797, -0.9311800003051758, 1.8960661888122559, -0.008992496877908707, -1.5161372423171997], [-0.05058002471923828, -0.2269899845123291, -0.8298521041870117, 1.7180380821228027, -0.05058002471923828, -0.1487560272216797, -0.9311800003051758, 1.8945322036743164, -0.009951416403055191, -1.5161372423171997], [0, 0, 0, 0, 0, 0, 0, 0, 0, -1.5707963267948966], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5707963267948966], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5707963267948966], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5707963267948966], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5707963267948966], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5707963267948966], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5707963267948966], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5707963267948966], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5707963267948966], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5707963267948966], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5707963267948966], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5707963267948966], [0, 0, 0, 0, 0, 0, 0, 0, 0, -1.5707963267948966]] -------------------------------------------------------------------------------- /joint_control/robot_pose_data/Belly: -------------------------------------------------------------------------------- 1 | (lp0 2 | (lp1 3 | F0.06600403785705566 4 | aF0.0061779022216796875 5 | aF0.07980990409851074 6 | aF2.0079641342163086 7 | aF0.06600403785705566 8 | aF0.0844118595123291 9 | aF0.09506607055664062 10 | aF1.8976001739501953 11 | aF-0.018579784780740738 12 | aF1.4904650449752808 13 | aa(lp2 14 | F0.06600403785705566 15 | aF0.007711887359619141 16 | aF0.07827591896057129 17 | aF2.0079641342163086 18 | aF0.06600403785705566 19 | aF0.08594608306884766 20 | aF0.09353208541870117 21 | aF1.8976001739501953 22 | aF-0.018579784780740738 23 | aF1.490273356437683 24 | aa(lp3 25 | F0.06600403785705566 26 | aF0.0061779022216796875 27 | aF0.07827591896057129 28 | aF2.0079641342163086 29 | aF0.06600403785705566 30 | aF0.08594608306884766 31 | aF0.09506607055664062 32 | aF1.8960661888122559 33 | aF-0.018579784780740738 34 | aF1.490273356437683 35 | aa(lp4 36 | F0.06600403785705566 37 | aF0.007711887359619141 38 | aF0.07827591896057129 39 | aF2.009498119354248 40 | aF0.06600403785705566 41 | aF0.0844118595123291 42 | aF0.09506607055664062 43 | aF1.8976001739501953 44 | aF-0.018771473318338394 45 | aF1.4900816679000854 46 | aa(lp5 47 | F0.06600403785705566 48 | aF0.0061779022216796875 49 | aF0.07827591896057129 50 | aF2.0079641342163086 51 | aF0.06600403785705566 52 | aF0.0844118595123291 53 | aF0.09506607055664062 54 | aF1.8960661888122559 55 | aF-0.018771473318338394 56 | aF1.4864386320114136 57 | aa(lp6 58 | F0.06600403785705566 59 | aF0.0061779022216796875 60 | aF0.07980990409851074 61 | aF2.0079641342163086 62 | aF0.06600403785705566 63 | aF0.08594608306884766 64 | aF0.09506607055664062 65 | aF1.8960661888122559 66 | aF-0.018579784780740738 67 | aF1.4864386320114136 68 | aa(lp7 69 | F0.06600403785705566 70 | aF0.0061779022216796875 71 | aF0.07827591896057129 72 | aF2.0079641342163086 73 | aF0.06600403785705566 74 | aF0.08594608306884766 75 | aF0.09353208541870117 76 | aF1.8976001739501953 77 | aF-0.018579784780740738 78 | aF1.4868220090866089 79 | aa(lp8 80 | F0.06600403785705566 81 | aF0.0061779022216796875 82 | aF0.07827591896057129 83 | aF2.0079641342163086 84 | aF0.06600403785705566 85 | aF0.08594608306884766 86 | aF0.09353208541870117 87 | aF1.8960661888122559 88 | aF-0.02068883553147316 89 | aF1.4862464666366577 90 | aa(lp9 91 | F0.06600403785705566 92 | aF0.007711887359619141 93 | aF0.07827591896057129 94 | aF2.0079641342163086 95 | aF0.06600403785705566 96 | aF0.0844118595123291 97 | aF0.09353208541870117 98 | aF1.8976001739501953 99 | aF-0.01973039284348488 100 | aF1.4801105260849 101 | aa(lp10 102 | F0.06600403785705566 103 | aF0.0061779022216796875 104 | aF0.07827591896057129 105 | aF2.009498119354248 106 | aF0.06600403785705566 107 | aF0.0844118595123291 108 | aF0.09506607055664062 109 | aF1.8960661888122559 110 | aF-0.01973039284348488 111 | aF1.4801105260849 112 | aa(lp11 113 | F0.0 114 | aF0.0 115 | aF0.0 116 | aF0.0 117 | aF0.0 118 | aF0.0 119 | aF0.0 120 | aF0.0 121 | aF0.0 122 | aF1.5707963267948966 123 | aag11 124 | ag11 125 | ag11 126 | ag11 127 | ag11 128 | ag11 129 | ag11 130 | ag11 131 | a. -------------------------------------------------------------------------------- /kinematics/forward_kinematics.py: -------------------------------------------------------------------------------- 1 | '''In this exercise you need to implement forward kinematics for NAO robot 2 | 3 | * Tasks: 4 | 1. complete the kinematics chain definition (self.chains in class ForwardKinematicsAgent) 5 | The documentation from Aldebaran is here: 6 | http://doc.aldebaran.com/2-1/family/robots/bodyparts.html#effector-chain 7 | 2. implement the calculation of local transformation for one joint in function 8 | ForwardKinematicsAgent.local_trans. The necessary documentation are: 9 | http://doc.aldebaran.com/2-1/family/nao_h21/joints_h21.html 10 | http://doc.aldebaran.com/2-1/family/nao_h21/links_h21.html 11 | 3. complete function ForwardKinematicsAgent.forward_kinematics, save the transforms of all body parts in torso 12 | coordinate into self.transforms of class ForwardKinematicsAgent 13 | 14 | * Hints: 15 | 1. the local_trans has to consider different joint axes and link parameters for different joints 16 | 2. Please use radians and meters as unit. 17 | ''' 18 | 19 | # add PYTHONPATH 20 | import os 21 | import sys 22 | sys.path.append(os.path.join(os.path.abspath(os.path.dirname(__file__)), '..', 'joint_control')) 23 | 24 | from numpy.matlib import matrix, identity 25 | 26 | from recognize_posture import PostureRecognitionAgent 27 | 28 | 29 | class ForwardKinematicsAgent(PostureRecognitionAgent): 30 | def __init__(self, simspark_ip='localhost', 31 | simspark_port=3100, 32 | teamname='DAInamite', 33 | player_id=0, 34 | sync_mode=True): 35 | super(ForwardKinematicsAgent, self).__init__(simspark_ip, simspark_port, teamname, player_id, sync_mode) 36 | self.transforms = {n: identity(4) for n in self.joint_names} 37 | 38 | # chains defines the name of chain and joints of the chain 39 | self.chains = {'Head': ['HeadYaw', 'HeadPitch'] 40 | # YOUR CODE HERE 41 | } 42 | 43 | def think(self, perception): 44 | self.forward_kinematics(perception.joint) 45 | return super(ForwardKinematicsAgent, self).think(perception) 46 | 47 | def local_trans(self, joint_name, joint_angle): 48 | '''calculate local transformation of one joint 49 | 50 | :param str joint_name: the name of joint 51 | :param float joint_angle: the angle of joint in radians 52 | :return: transformation 53 | :rtype: 4x4 matrix 54 | ''' 55 | T = identity(4) 56 | # YOUR CODE HERE 57 | 58 | return T 59 | 60 | def forward_kinematics(self, joints): 61 | '''forward kinematics 62 | 63 | :param joints: {joint_name: joint_angle} 64 | ''' 65 | for chain_joints in self.chains.values(): 66 | T = identity(4) 67 | for joint in chain_joints: 68 | angle = joints[joint] 69 | Tl = self.local_trans(joint, angle) 70 | # YOUR CODE HERE 71 | 72 | self.transforms[joint] = T 73 | 74 | if __name__ == '__main__': 75 | agent = ForwardKinematicsAgent() 76 | agent.run() 77 | -------------------------------------------------------------------------------- /joint_control/robot_pose_data/Right: -------------------------------------------------------------------------------- 1 | (lp0 2 | (lp1 3 | F0.10588788986206055 4 | aF0.33905601501464844 5 | aF-0.49083805084228516 6 | aF-0.13196587562561035 7 | aF0.10588788986206055 8 | aF0.3559298515319824 9 | aF-0.6750020980834961 10 | aF0.052197933197021484 11 | aF1.3264503479003906 12 | aF0.08901166915893555 13 | aa(lp2 14 | F0.10588788986206055 15 | aF0.33905601501464844 16 | aF-0.49083805084228516 17 | aF-0.13196587562561035 18 | aF0.10588788986206055 19 | aF0.3559298515319824 20 | aF-0.6750020980834961 21 | aF0.05066394805908203 22 | aF1.3264503479003906 23 | aF0.08901166915893555 24 | aa(lp3 25 | F0.10588788986206055 26 | aF0.3405900001525879 27 | aF-0.49083805084228516 28 | aF-0.13196587562561035 29 | aF0.10588788986206055 30 | aF0.3559298515319824 31 | aF-0.6750020980834961 32 | aF0.052197933197021484 33 | aF1.3264503479003906 34 | aF0.08901166915893555 35 | aa(lp4 36 | F0.10588788986206055 37 | aF0.33905601501464844 38 | aF-0.49083805084228516 39 | aF-0.13196587562561035 40 | aF0.10588788986206055 41 | aF0.357464075088501 42 | aF-0.6734678745269775 43 | aF0.052197933197021484 44 | aF1.3159785270690918 45 | aF0.09075689315795898 46 | aa(lp5 47 | F0.10588788986206055 48 | aF0.33905601501464844 49 | aF-0.49083805084228516 50 | aF-0.13196587562561035 51 | aF0.10588788986206055 52 | aF0.357464075088501 53 | aF-0.6750020980834961 54 | aF0.052197933197021484 55 | aF1.3159785270690918 56 | aF0.09075689315795898 57 | aa(lp6 58 | F0.10588788986206055 59 | aF0.3405900001525879 60 | aF-0.49083805084228516 61 | aF-0.13196587562561035 62 | aF0.10588788986206055 63 | aF0.3559298515319824 64 | aF-0.6750020980834961 65 | aF0.052197933197021484 66 | aF1.3159785270690918 67 | aF0.09075689315795898 68 | aa(lp7 69 | F0.10588788986206055 70 | aF0.33905601501464844 71 | aF-0.49083805084228516 72 | aF-0.13196587562561035 73 | aF0.10588788986206055 74 | aF0.3559298515319824 75 | aF-0.6750020980834961 76 | aF0.052197933197021484 77 | aF1.3159785270690918 78 | aF0.09075689315795898 79 | aa(lp8 80 | F0.10588788986206055 81 | aF0.3405900001525879 82 | aF-0.4893040657043457 83 | aF-0.13196587562561035 84 | aF0.10588788986206055 85 | aF0.3559298515319824 86 | aF-0.6750020980834961 87 | aF0.052197933197021484 88 | aF1.3159785270690918 89 | aF0.09075689315795898 90 | aa(lp9 91 | F0.10588788986206055 92 | aF0.33905601501464844 93 | aF-0.49083805084228516 94 | aF-0.13196587562561035 95 | aF0.10588788986206055 96 | aF0.3559298515319824 97 | aF-0.6750020980834961 98 | aF0.052197933197021484 99 | aF1.3159785270690918 100 | aF0.08901166915893555 101 | aa(lp10 102 | F0.10588788986206055 103 | aF0.33905601501464844 104 | aF-0.49083805084228516 105 | aF-0.13196587562561035 106 | aF0.10588788986206055 107 | aF0.3559298515319824 108 | aF-0.6750020980834961 109 | aF0.052197933197021484 110 | aF1.3177237510681152 111 | aF0.08901166915893555 112 | aa(lp11 113 | F-0.1579599380493164 114 | aF-0.3251659870147705 115 | aF-0.7562201023101807 116 | aF2.083130121231079 117 | aF-0.15949392318725586 118 | aF0.10895586013793945 119 | aF-1.540177822113037 120 | aF2.1353702545166016 121 | aF1.4346609115600586 122 | aF0.1099553108215332 123 | aa. -------------------------------------------------------------------------------- /joint_control/robot_pose_data/Stand: -------------------------------------------------------------------------------- 1 | (lp0 2 | (lp1 3 | F-0.23926210403442383 4 | aF0.14883995056152344 5 | aF0.21173405647277832 6 | aF-0.09054803848266602 7 | aF-0.23926210403442383 8 | aF-0.056715965270996094 9 | aF0.2118614763021469 10 | aF-0.07665801048278809 11 | aF-0.005560700315982103 12 | aF-0.013422664254903793 13 | aa(lp2 14 | F-0.23926210403442383 15 | aF0.14883995056152344 16 | aF0.21173405647277832 17 | aF-0.09054803848266602 18 | aF-0.23926210403442383 19 | aF-0.05824995040893555 20 | aF0.21032725274562836 21 | aF-0.07665801048278809 22 | aF-0.005560700315982103 23 | aF-0.013422664254903793 24 | aa(lp3 25 | F-0.23926210403442383 26 | aF0.14883995056152344 27 | aF0.21173405647277832 28 | aF-0.09054803848266602 29 | aF-0.23926210403442383 30 | aF-0.05824995040893555 31 | aF0.2118614763021469 32 | aF-0.07665801048278809 33 | aF-0.005560700315982103 34 | aF-0.013422664254903793 35 | aa(lp4 36 | F-0.23926210403442383 37 | aF0.14883995056152344 38 | aF0.21173405647277832 39 | aF-0.09054803848266602 40 | aF-0.23926210403442383 41 | aF-0.05824995040893555 42 | aF0.21032725274562836 43 | aF-0.07665801048278809 44 | aF-0.00575238885357976 45 | aF-0.013422664254903793 46 | aa(lp5 47 | F-0.23926210403442383 48 | aF0.14883995056152344 49 | aF0.21173405647277832 50 | aF-0.09054803848266602 51 | aF-0.23926210403442383 52 | aF-0.05824995040893555 53 | aF0.21032725274562836 54 | aF-0.07665801048278809 55 | aF-0.00575238885357976 56 | aF-0.013422664254903793 57 | aa(lp6 58 | F-0.23926210403442383 59 | aF0.14883995056152344 60 | aF0.21173405647277832 61 | aF-0.09054803848266602 62 | aF-0.23926210403442383 63 | aF-0.05824995040893555 64 | aF0.2118614763021469 65 | aF-0.07665801048278809 66 | aF-0.00575238885357976 67 | aF-0.013422664254903793 68 | aa(lp7 69 | F-0.23926210403442383 70 | aF0.14883995056152344 71 | aF0.21173405647277832 72 | aF-0.09054803848266602 73 | aF-0.23926210403442383 74 | aF-0.056715965270996094 75 | aF0.2118614763021469 76 | aF-0.07665801048278809 77 | aF-0.00575238885357976 78 | aF-0.013422664254903793 79 | aa(lp8 80 | F-0.23926210403442383 81 | aF0.14730596542358398 82 | aF0.21173405647277832 83 | aF-0.09054803848266602 84 | aF-0.23926210403442383 85 | aF-0.05824995040893555 86 | aF0.2118614763021469 87 | aF-0.07665801048278809 88 | aF-0.005944077391177416 89 | aF-0.013422664254903793 90 | aa(lp9 91 | F-0.23926210403442383 92 | aF0.14883995056152344 93 | aF0.21173405647277832 94 | aF-0.09054803848266602 95 | aF-0.23926210403442383 96 | aF-0.056715965270996094 97 | aF0.2118614763021469 98 | aF-0.07665801048278809 99 | aF-0.006135765928775072 100 | aF-0.011696990579366684 101 | aa(lp10 102 | F-0.24079608917236328 103 | aF0.14883995056152344 104 | aF0.21173405647277832 105 | aF-0.09054803848266602 106 | aF-0.23926210403442383 107 | aF-0.056715965270996094 108 | aF0.2118614763021469 109 | aF-0.07665801048278809 110 | aF-0.007669751066714525 111 | aF-0.015531715005636215 112 | aa(lp11 113 | F-0.23926210403442383 114 | aF0.0583338737487793 115 | aF0.21173405647277832 116 | aF-0.07980990409851074 117 | aF-0.23926210403442383 118 | aF-0.1487560272216797 119 | aF0.2118614763021469 120 | aF-0.08893013000488281 121 | aF0.010546383447945118 122 | aF-0.017257388681173325 123 | aa. -------------------------------------------------------------------------------- /joint_control/robot_pose_data/Back: -------------------------------------------------------------------------------- 1 | (lp0 2 | (lp1 3 | F-0.05058002471923828 4 | aF-0.2269899845123291 5 | aF-0.8298521041870117 6 | aF1.7180380821228027 7 | aF-0.05058002471923828 8 | aF-0.1487560272216797 9 | aF-0.9311800003051758 10 | aF1.8945322036743164 11 | aF-0.008992496877908707 12 | aF-1.516520619392395 13 | aa(lp2 14 | F-0.05058002471923828 15 | aF-0.2269899845123291 16 | aF-0.8298521041870117 17 | aF1.7180380821228027 18 | aF-0.05058002471923828 19 | aF-0.1487560272216797 20 | aF-0.9311800003051758 21 | aF1.8960661888122559 22 | aF-0.006883446592837572 23 | aF-1.5203558206558228 24 | aa(lp3 25 | F-0.05058002471923828 26 | aF-0.2269899845123291 27 | aF-0.8298521041870117 28 | aF1.7165040969848633 29 | aF-0.05058002471923828 30 | aF-0.1487560272216797 31 | aF-0.9311800003051758 32 | aF1.8945322036743164 33 | aF-0.006883446592837572 34 | aF-1.520164132118225 35 | aa(lp4 36 | F-0.05058002471923828 37 | aF-0.2269899845123291 38 | aF-0.8298521041870117 39 | aF1.7165040969848633 40 | aF-0.05058002471923828 41 | aF-0.1487560272216797 42 | aF-0.9311800003051758 43 | aF1.8945322036743164 44 | aF-0.007075135130435228 45 | aF-1.5199724435806274 46 | aa(lp5 47 | F-0.05058002471923828 48 | aF-0.2269899845123291 49 | aF-0.8298521041870117 50 | aF1.7165040969848633 51 | aF-0.05058002471923828 52 | aF-0.1487560272216797 53 | aF-0.9296460151672363 54 | aF1.8945322036743164 55 | aF-0.007266823668032885 56 | aF-1.5199724435806274 57 | aa(lp6 58 | F-0.05058002471923828 59 | aF-0.2269899845123291 60 | aF-0.8298521041870117 61 | aF1.7180380821228027 62 | aF-0.05058002471923828 63 | aF-0.1487560272216797 64 | aF-0.9311800003051758 65 | aF1.8945322036743164 66 | aF-0.007266823668032885 67 | aF-1.5197802782058716 68 | aa(lp7 69 | F-0.05058002471923828 70 | aF-0.2269899845123291 71 | aF-0.8298521041870117 72 | aF1.7165040969848633 73 | aF-0.05058002471923828 74 | aF-0.1487560272216797 75 | aF-0.9311800003051758 76 | aF1.8945322036743164 77 | aF-0.006883446592837572 78 | aF-1.5216976404190063 79 | aa(lp8 80 | F-0.05058002471923828 81 | aF-0.22852396965026855 82 | aF-0.8298521041870117 83 | aF1.7165040969848633 84 | aF-0.05058002471923828 85 | aF-0.1487560272216797 86 | aF-0.9311800003051758 87 | aF1.8960661888122559 88 | aF-0.008992496877908707 89 | aF-1.5134526491165161 90 | aa(lp9 91 | F-0.05058002471923828 92 | aF-0.2269899845123291 93 | aF-0.8298521041870117 94 | aF1.7165040969848633 95 | aF-0.05058002471923828 96 | aF-0.1487560272216797 97 | aF-0.9311800003051758 98 | aF1.8960661888122559 99 | aF-0.008992496877908707 100 | aF-1.5161372423171997 101 | aa(lp10 102 | F-0.05058002471923828 103 | aF-0.2269899845123291 104 | aF-0.8298521041870117 105 | aF1.7180380821228027 106 | aF-0.05058002471923828 107 | aF-0.1487560272216797 108 | aF-0.9311800003051758 109 | aF1.8945322036743164 110 | aF-0.009951416403055191 111 | aF-1.5161372423171997 112 | aa(lp11 113 | I0 114 | aI0 115 | aI0 116 | aI0 117 | aI0 118 | aI0 119 | aI0 120 | aI0 121 | aI0 122 | aF-1.5707963267948966 123 | aa(lp12 124 | F0.0 125 | aF0.0 126 | aF0.0 127 | aF0.0 128 | aF0.0 129 | aF0.0 130 | aF0.0 131 | aF0.0 132 | aF0.0 133 | aF-1.5707963267948966 134 | aag12 135 | ag12 136 | ag12 137 | ag12 138 | ag12 139 | ag12 140 | ag12 141 | ag12 142 | ag12 143 | ag12 144 | a(lp13 145 | I0 146 | aI0 147 | aI0 148 | aI0 149 | aI0 150 | aI0 151 | aI0 152 | aI0 153 | aI0 154 | aF-1.5707963267948966 155 | aa. -------------------------------------------------------------------------------- /joint_control/pid.py: -------------------------------------------------------------------------------- 1 | '''In this exercise you need to implement the PID controller for joints of robot. 2 | 3 | * Task: 4 | 1. complete the control function in PIDController with prediction 5 | 2. adjust PID parameters for NAO in simulation 6 | 7 | * Hints: 8 | 1. the motor in simulation can simple modelled by angle(t) = angle(t-1) + speed * dt 9 | 2. use self.y to buffer model prediction 10 | ''' 11 | 12 | # add PYTHONPATH 13 | import os 14 | import sys 15 | sys.path.append(os.path.join(os.path.abspath(os.path.dirname(__file__)), '..', 'software_installation')) 16 | 17 | import numpy as np 18 | from collections import deque 19 | from spark_agent import SparkAgent, JOINT_CMD_NAMES 20 | 21 | 22 | class PIDController(object): 23 | '''a discretized PID controller, it controls an array of servos, 24 | e.g. input is an array and output is also an array 25 | ''' 26 | def __init__(self, dt, size): 27 | ''' 28 | @param dt: step time 29 | @param size: number of control values 30 | @param delay: delay in number of steps 31 | ''' 32 | self.dt = dt 33 | self.u = np.zeros(size) 34 | self.e1 = np.zeros(size) 35 | self.e2 = np.zeros(size) 36 | # ADJUST PARAMETERS BELOW 37 | delay = 0 38 | self.Kp = 0 39 | self.Ki = 0 40 | self.Kd = 0 41 | self.y = deque(np.zeros(size), maxlen=delay + 1) 42 | 43 | def set_delay(self, delay): 44 | ''' 45 | @param delay: delay in number of steps 46 | ''' 47 | self.y = deque(self.y, delay + 1) 48 | 49 | def control(self, target, sensor): 50 | '''apply PID control 51 | @param target: reference values 52 | @param sensor: current values from sensor 53 | @return control signal 54 | ''' 55 | # YOUR CODE HERE 56 | 57 | return self.u 58 | 59 | 60 | class PIDAgent(SparkAgent): 61 | def __init__(self, simspark_ip='localhost', 62 | simspark_port=3100, 63 | teamname='DAInamite', 64 | player_id=0, 65 | sync_mode=True): 66 | super(PIDAgent, self).__init__(simspark_ip, simspark_port, teamname, player_id, sync_mode) 67 | self.joint_names = JOINT_CMD_NAMES.keys() 68 | number_of_joints = len(self.joint_names) 69 | self.joint_controller = PIDController(dt=0.01, size=number_of_joints) 70 | self.target_joints = {k: 0 for k in self.joint_names} 71 | 72 | def think(self, perception): 73 | action = super(PIDAgent, self).think(perception) 74 | '''calculate control vector (speeds) from 75 | perception.joint: current joints' positions (dict: joint_id -> position (current)) 76 | self.target_joints: target positions (dict: joint_id -> position (target)) ''' 77 | joint_angles = np.asarray( 78 | [perception.joint[joint_id] for joint_id in JOINT_CMD_NAMES]) 79 | target_angles = np.asarray([self.target_joints.get(joint_id, 80 | perception.joint[joint_id]) for joint_id in JOINT_CMD_NAMES]) 81 | u = self.joint_controller.control(target_angles, joint_angles) 82 | action.speed = dict(zip(JOINT_CMD_NAMES.keys(), u)) # dict: joint_id -> speed 83 | return action 84 | 85 | 86 | if __name__ == '__main__': 87 | agent = PIDAgent() 88 | agent.target_joints['HeadYaw'] = 1.0 89 | agent.run() 90 | -------------------------------------------------------------------------------- /software_installation/README.md: -------------------------------------------------------------------------------- 1 | # 1: software installation 2 | 3 | ## Python 4 | First you have to [setup python](http://learnpythonthehardway.org/book/ex0.html), then install python libraries. 5 | The recommended way to install python libraries is using [pip](https://pip.pypa.io/en/stable/). 6 | 7 | #### Ubuntu 8 | 9 | ``` 10 | sudo apt-get install python-pip 11 | pip install numpy matplotlib ipython jupyter 12 | ``` 13 | #### Windows 14 | 1. download and install python: https://www.python.org/download/windows/ 15 | 2. install pip: https://pip.pypa.io/en/latest/installing.html 16 | 3. install numpy and matplotlib 17 | 18 | ``` 19 | python -m pip install numpy matplotlib ipython jupyter 20 | ``` 21 | 22 | ## Learn Python 23 | If you are new to python, you can follow [Introduction to Python](http://introtopython.org/). If you want a little more depth, [Python Tutorial](http://docs.python.org/2/tutorial/) is a great place to start, We also recommend to [Learn Python the Hard Way](http://learnpythonthehardway.org/book/). 24 | 25 | You can try ipython notebooks that I used in the lecture by starting ```ipython notebook``` in this folder or [open in Colab]((https://colab.research.google.com/notebooks/welcome.ipynb). 26 | 27 | * [python_basic.ipynb](./python_basic.ipynb) [![Open In Colab](https://colab.research.google.com/assets/colab-badge.svg)](https://colab.research.google.com/github/DAInamite/programming-humanoid-robot-in-python/blob/master/software_installation/python_basic.ipynb) 28 | * [numpy_baisc.ipynb](./numpy_baisc.ipynb) [![Open In Colab](https://colab.research.google.com/assets/colab-badge.svg)](https://colab.research.google.com/github/DAInamite/programming-humanoid-robot-in-python/blob/master/software_installation/numpy_baisc.ipynb) 29 | * [matplotlib_basic.ipynb](./matplotlib_basic.ipynb) [![Open In Colab](https://colab.research.google.com/assets/colab-badge.svg)](https://colab.research.google.com/github/DAInamite/programming-humanoid-robot-in-python/blob/master/software_installation/matplotlib_basic.ipynb) 30 | 31 | 32 | ## SimSpark 33 | 34 | [SimSpark](http://simspark.sourceforge.net/) is a generic simulator for various multiagent simulations. It supports developing physical simulations for AI and robotics research with an open-source application framework. We use [customized version](https://github.com/xuyuan/SimSpark-SPL) which has NAO V4. 35 | 36 | #### Linux 37 | 1. download [simspark.AppImage](https://github.com/BerlinUnited/SimSpark-SPL/releases/) 38 | 2. [Make it executable and double-click it](https://github.com/AppImage/AppImageKit/wiki#-what-is-an-appimage) 39 | 40 | #### Windows 41 | 1. download [zip package](https://github.com/BerlinUnited/SimSpark-SPL/releases/) 42 | 2. extract the zip package 43 | 3. execute *SimSparkSPL.bat* to start simspark 44 | 45 | #### From source code (Other operation systems) 46 | 1. download source code from https://github.com/xuyuan/SimSpark-SPL 47 | 2. follow the instruction in https://gitlab.com/robocup-sim/SimSpark/wikis/home 48 | 49 | 50 | ### Try out sample agent 51 | #### start sample agent 52 | 1. start simspark 53 | * [learn how to use simspark](https://gitlab.com/robocup-sim/SimSpark/-/wikis/Monitor) 54 | 55 | 2. start a console (cmd in windows) 56 | 3. go to the *software_installtion* source code folder 57 | ``` 58 | cd software_installtion 59 | ``` 60 | 61 | 4. start sample agent: 62 | ``` 63 | python spark_agent.py 64 | ``` 65 | 66 | Now, the spark_agent is connected to simspark, and you can see a robot in the simulation, we are ready to program it. 67 | 68 | 69 | 70 | 71 | -------------------------------------------------------------------------------- /joint_control/robot_pose_data_json/Left: -------------------------------------------------------------------------------- 1 | [[0.004643917083740234, -0.3619821071624756, -1.4741320610046387, 2.142956018447876, 0.004643917083740234, -0.11040592193603516, -0.8713541030883789, 1.5708580017089844, -0.6527528762817383, 0.0820302963256836], [0.004643917083740234, -0.3619821071624756, -1.4741320610046387, 2.1414220333099365, 0.004643917083740234, -0.11040592193603516, -0.8713541030883789, 1.5708580017089844, -0.6544981002807617, 0.0820302963256836], [0.004643917083740234, -0.3619821071624756, -1.4741320610046387, 2.1414220333099365, 0.004643917083740234, -0.11040592193603516, -0.8713541030883789, 1.5708580017089844, -0.6544981002807617, 0.08377552032470703], [0.004643917083740234, -0.3619821071624756, -1.4741320610046387, 2.1414220333099365, 0.004643917083740234, -0.11040592193603516, -0.8713541030883789, 1.5708580017089844, -0.6544981002807617, 0.08028507232666016], [0.004643917083740234, -0.3619821071624756, -1.4741320610046387, 2.1414220333099365, 0.004643917083740234, -0.11040592193603516, -0.8713541030883789, 1.5708580017089844, -0.6544981002807617, 0.08028507232666016], [0.004643917083740234, -0.3619821071624756, -1.4741320610046387, 2.1414220333099365, 0.004643917083740234, -0.11040592193603516, -0.8713541030883789, 1.5708580017089844, -0.6527528762817383, 0.08377552032470703], [0.004643917083740234, -0.3619821071624756, -1.4741320610046387, 2.1414220333099365, 0.004643917083740234, -0.11040592193603516, -0.8713541030883789, 1.5708580017089844, -0.6527528762817383, 0.08377552032470703], [0.004643917083740234, -0.3619821071624756, -1.4741320610046387, 2.1414220333099365, 0.004643917083740234, -0.11040592193603516, -0.8713541030883789, 1.5708580017089844, -0.6527528762817383, 0.08377552032470703], [0.004643917083740234, -0.3619821071624756, -1.4741320610046387, 2.1414220333099365, 0.004643917083740234, -0.11040592193603516, -0.8713541030883789, 1.5708580017089844, -0.6527528762817383, 0.0820302963256836], [0.004643917083740234, -0.3619821071624756, -1.4741320610046387, 2.1414220333099365, 0.004643917083740234, -0.11040592193603516, -0.8713541030883789, 1.5708580017089844, -0.6527528762817383, 0.0820302963256836], [0.14730596542358398, 0.6796040534973145, -1.4189081192016602, -0.11202406883239746, 0.14730596542358398, 0.3697359561920166, -0.7332940101623535, 0.052197933197021484, -1.3997540473937988, -0.06981325149536133], [-0.36965203285217285, -0.3512439727783203, -0.29755401611328125, -0.12889790534973145, -0.36965203285217285, 0.1994619369506836, 0.3880600929260254, 0.04912996292114258, -1.3892817497253418, 0.07853937149047852], [-0.3711860179901123, -0.3512439727783203, -0.2990880012512207, -0.12889790534973145, -0.3711860179901123, 0.1994619369506836, 0.3880600929260254, 0.04912996292114258, -1.3945178985595703, 0.07853937149047852], [-0.3711860179901123, -0.3512439727783203, -0.29755401611328125, -0.12889790534973145, -0.3711860179901123, 0.1994619369506836, 0.3880600929260254, 0.04912996292114258, -1.3945178985595703, 0.07155847549438477], [0.0614018440246582, -0.29448604583740234, -0.09660005569458008, -0.13196587562561035, 0.0614018440246582, -0.11807609349489212, 0.25153398513793945, 0.047595977783203125, -1.2915434837341309, 0.21292972564697266], [0.05986785888671875, -0.29448604583740234, -0.09660005569458008, -0.1304318904876709, 0.05986785888671875, -0.11807609349489212, 0.25, 0.04912996292114258, -1.281071662902832, 0.22165679931640625], [-0.22238802909851074, -0.22238802909851074, -0.11654210090637207, -0.1304318904876709, -0.22238802909851074, 0.03992605209350586, 0.4724299907684326, 0.047595977783203125, -1.2426743507385254, -0.2373647689819336], [0.0353238582611084, -0.30675792694091797, -0.5859460830688477, 1.4204421043395996, 0.0353238582611084, -0.18710613250732422, -0.4050178527832031, 1.2809319496154785, -1.3369221687316895, 0.00698089599609375], [0.0353238582611084, -0.30675792694091797, -0.5859460830688477, 1.4204421043395996, 0.0353238582611084, -0.18710613250732422, -0.4050178527832031, 1.2809319496154785, -1.338667392730713, 0.0017452239990234375], [0.0353238582611084, -0.30675792694091797, -0.5859460830688477, 1.4204421043395996, 0.0353238582611084, -0.18710613250732422, -0.4050178527832031, 1.2809319496154785, -1.338667392730713, 0.003490447998046875]] -------------------------------------------------------------------------------- /joint_control/robot_pose_data_json/Sit: -------------------------------------------------------------------------------- 1 | [[-0.7562201023101807, 0.7839159965515137, -1.630600094795227, 0.2607381343841553, -0.7562201023101807, 0.09975194931030273, -1.5708580017089844, 0.1074218824505806, -0.03839683532714844, 0.438077449798584], [-0.7562201023101807, 0.7839159965515137, -1.630600094795227, 0.2607381343841553, -0.7562201023101807, 0.09975194931030273, -1.5708580017089844, 0.1074218824505806, -0.036651611328125, 0.438077449798584], [-0.7562201023101807, 0.7839159965515137, -1.630600094795227, 0.2607381343841553, -0.7562201023101807, 0.09821796417236328, -1.5708580017089844, 0.1074218824505806, -0.036651611328125, 0.43633222579956055], [-0.7562201023101807, 0.7823820114135742, -1.630600094795227, 0.2607381343841553, -0.7562201023101807, 0.09975194931030273, -1.5708580017089844, 0.1074218824505806, -0.03839683532714844, 0.44156789779663086], [-0.7562201023101807, 0.7839159965515137, -1.630600094795227, 0.2607381343841553, -0.7562201023101807, 0.09975194931030273, -1.5708580017089844, 0.1074218824505806, -0.03839683532714844, 0.4398226737976074], [-0.7562201023101807, 0.7839159965515137, -1.630600094795227, 0.2607381343841553, -0.7562201023101807, 0.09821796417236328, -1.5708580017089844, 0.1074218824505806, -0.03839683532714844, 0.438077449798584], [-0.7562201023101807, 0.7823820114135742, -1.630600094795227, 0.2607381343841553, -0.7562201023101807, 0.09975194931030273, -1.5708580017089844, 0.1074218824505806, -0.03839683532714844, 0.44156789779663086], [-0.7562201023101807, 0.7823820114135742, -1.630600094795227, 0.2607381343841553, -0.7562201023101807, 0.09975194931030273, -1.5708580017089844, 0.1074218824505806, -0.03839683532714844, 0.4398226737976074], [-0.7562201023101807, 0.7839159965515137, -1.630600094795227, 0.2607381343841553, -0.7562201023101807, 0.09975194931030273, -1.5708580017089844, 0.1074218824505806, -0.03839683532714844, 0.4398226737976074], [-0.7562201023101807, 0.7839159965515137, -1.630600094795227, 0.2607381343841553, -0.7562201023101807, 0.09821796417236328, -1.5708580017089844, 0.1074218824505806, -0.03839683532714844, 0.43633222579956055], [-0.7562201023101807, 0.7823820114135742, -1.630600094795227, 0.2607381343841553, -0.7562201023101807, 0.09821796417236328, -1.5708580017089844, 0.1074218824505806, -0.03839683532714844, 0.43284130096435547], [-0.7562201023101807, 0.7823820114135742, -1.630600094795227, 0.2607381343841553, -0.7562201023101807, 0.09975194931030273, -1.569324016571045, 0.1074218824505806, -0.041887760162353516, 0.438077449798584], [-0.7562201023101807, 0.7839159965515137, -1.630600094795227, 0.2607381343841553, -0.7562201023101807, 0.09821796417236328, -1.569324016571045, 0.1074218824505806, -0.041887760162353516, 0.43284130096435547], [-0.7562201023101807, 0.7823820114135742, -1.630600094795227, 0.2607381343841553, -0.7562201023101807, 0.09975194931030273, -1.5708580017089844, 0.1074218824505806, -0.04014253616333008, 0.4345865249633789], [-0.7577540874481201, 0.7839159965515137, -1.630600094795227, 0.2607381343841553, -0.7577540874481201, 0.09975194931030273, -1.5708580017089844, 0.1074218824505806, -0.04014253616333008, 0.43633222579956055], [-0.7562201023101807, 0.7823820114135742, -1.630600094795227, 0.2607381343841553, -0.7562201023101807, 0.09821796417236328, -1.5708580017089844, 0.1074218824505806, -0.04014253616333008, 0.438077449798584], [-0.7562201023101807, 0.7823820114135742, -1.630600094795227, 0.2607381343841553, -0.7562201023101807, 0.09821796417236328, -1.5708580017089844, 0.1074218824505806, -0.041887760162353516, 0.43284130096435547], [-0.7577540874481201, 0.7839159965515137, -1.630600094795227, 0.2607381343841553, -0.7577540874481201, 0.09975194931030273, -1.5708580017089844, 0.1074218824505806, -0.03839683532714844, 0.4345865249633789], [-0.7562201023101807, 0.7823820114135742, -1.630600094795227, 0.2607381343841553, -0.7562201023101807, 0.09821796417236328, -1.5708580017089844, 0.1074218824505806, -0.041887760162353516, 0.4345865249633789], [-0.6595780849456787, 0.1595778465270996, -1.5354920625686646, 1.5201520919799805, -0.6595780849456787, -0.06131792068481445, -1.4665460586547852, 1.3607001304626465, -0.013962268829345703, -0.34906625747680664], [-0.6595780849456787, 0.1595778465270996, -1.5354920625686646, 1.5201520919799805, -0.6595780849456787, -0.06131792068481445, -1.4665460586547852, 1.3607001304626465, -0.012217044830322266, -0.34906625747680664], [-0.6595780849456787, 0.1595778465270996, -1.5354920625686646, 1.5201520919799805, -0.6595780849456787, -0.06131792068481445, -1.4665460586547852, 1.3607001304626465, -0.012217044830322266, -0.3508114814758301], [-0.6503739356994629, -0.3052239418029785, -0.91115403175354, 0.34050607681274414, -0.6503739356994629, -0.0030260086059570312, -0.8606162071228027, 0.14117002487182617, -0.003490447998046875, -0.4066619873046875], [-0.6503739356994629, -0.3052239418029785, -0.91115403175354, 0.34050607681274414, -0.6503739356994629, -0.0030260086059570312, -0.8606162071228027, 0.14117002487182617, -0.0052356719970703125, -0.411898136138916], [-0.98785400390625, -0.3803901672363281, -0.5383920669555664, 0.28374814987182617, -0.98785400390625, 0.36820197105407715, -0.6059720516204834, 0.4326300621032715, 0.04188823699951172, -0.41364336013793945], [-0.3128941059112549, -0.230057954788208, -1.6704840660095215, 0.9663779735565186, -0.3128941059112549, 0.0353238582611084, -1.6228026151657104, 0.8299360275268555, 0.025310691446065903, -0.16758745908737183]] -------------------------------------------------------------------------------- /vision/getting_images.ipynb: -------------------------------------------------------------------------------- 1 | { 2 | "cells": [ 3 | { 4 | "cell_type": "code", 5 | "execution_count": null, 6 | "metadata": { 7 | "collapsed": true 8 | }, 9 | "outputs": [], 10 | "source": [ 11 | "%matplotlib inline\n", 12 | "\n", 13 | "import cv2\n", 14 | "import matplotlib.pyplot as plot" 15 | ] 16 | }, 17 | { 18 | "cell_type": "markdown", 19 | "metadata": {}, 20 | "source": [ 21 | "## getting one image from webcam" 22 | ] 23 | }, 24 | { 25 | "cell_type": "code", 26 | "execution_count": null, 27 | "metadata": { 28 | "collapsed": true 29 | }, 30 | "outputs": [], 31 | "source": [ 32 | "camera = cv2.VideoCapture(0)" 33 | ] 34 | }, 35 | { 36 | "cell_type": "code", 37 | "execution_count": null, 38 | "metadata": { 39 | "collapsed": true 40 | }, 41 | "outputs": [], 42 | "source": [ 43 | "retval, image = camera.read()" 44 | ] 45 | }, 46 | { 47 | "cell_type": "code", 48 | "execution_count": null, 49 | "metadata": { 50 | "collapsed": false 51 | }, 52 | "outputs": [], 53 | "source": [ 54 | "camera.release()" 55 | ] 56 | }, 57 | { 58 | "cell_type": "code", 59 | "execution_count": null, 60 | "metadata": { 61 | "collapsed": false 62 | }, 63 | "outputs": [], 64 | "source": [ 65 | "plot.imshow(image)" 66 | ] 67 | }, 68 | { 69 | "cell_type": "markdown", 70 | "metadata": {}, 71 | "source": [ 72 | "## save image and read it back" 73 | ] 74 | }, 75 | { 76 | "cell_type": "code", 77 | "execution_count": null, 78 | "metadata": { 79 | "collapsed": false 80 | }, 81 | "outputs": [], 82 | "source": [ 83 | "filename = 'first_image.png'\n", 84 | "cv2.imwrite(filename, image)" 85 | ] 86 | }, 87 | { 88 | "cell_type": "code", 89 | "execution_count": null, 90 | "metadata": { 91 | "collapsed": true 92 | }, 93 | "outputs": [], 94 | "source": [ 95 | "image2 = cv2.imread(filename)" 96 | ] 97 | }, 98 | { 99 | "cell_type": "code", 100 | "execution_count": null, 101 | "metadata": { 102 | "collapsed": false 103 | }, 104 | "outputs": [], 105 | "source": [ 106 | "plot.imshow(image)" 107 | ] 108 | }, 109 | { 110 | "cell_type": "markdown", 111 | "metadata": {}, 112 | "source": [ 113 | "# image data format" 114 | ] 115 | }, 116 | { 117 | "cell_type": "code", 118 | "execution_count": null, 119 | "metadata": { 120 | "collapsed": false 121 | }, 122 | "outputs": [], 123 | "source": [ 124 | "type(image)" 125 | ] 126 | }, 127 | { 128 | "cell_type": "code", 129 | "execution_count": null, 130 | "metadata": { 131 | "collapsed": false 132 | }, 133 | "outputs": [], 134 | "source": [ 135 | "image.shape, image.dtype" 136 | ] 137 | }, 138 | { 139 | "cell_type": "markdown", 140 | "metadata": {}, 141 | "source": [ 142 | "# color space" 143 | ] 144 | }, 145 | { 146 | "cell_type": "code", 147 | "execution_count": null, 148 | "metadata": { 149 | "collapsed": false 150 | }, 151 | "outputs": [], 152 | "source": [ 153 | "rgb_image = cv2.cvtColor(image, cv2.COLOR_BGR2RGB)\n", 154 | "plot.imshow(rgb_image)" 155 | ] 156 | }, 157 | { 158 | "cell_type": "code", 159 | "execution_count": null, 160 | "metadata": { 161 | "collapsed": false 162 | }, 163 | "outputs": [], 164 | "source": [ 165 | "r_image = rgb_image[:, :, 0]\n", 166 | "plot.imshow(r_image, cmap='gray')" 167 | ] 168 | }, 169 | { 170 | "cell_type": "code", 171 | "execution_count": null, 172 | "metadata": { 173 | "collapsed": false 174 | }, 175 | "outputs": [], 176 | "source": [ 177 | "rgb_image[:, :, 1:] = 0\n", 178 | "plot.imshow(rgb_image)" 179 | ] 180 | }, 181 | { 182 | "cell_type": "markdown", 183 | "metadata": {}, 184 | "source": [ 185 | "## Pixels" 186 | ] 187 | }, 188 | { 189 | "cell_type": "code", 190 | "execution_count": null, 191 | "metadata": { 192 | "collapsed": false 193 | }, 194 | "outputs": [], 195 | "source": [ 196 | "rgb_image = cv2.cvtColor(image, cv2.COLOR_BGR2RGB)\n", 197 | "rgb_image[100:200, 100:200, 0] = 255\n", 198 | "plot.imshow(rgb_image)" 199 | ] 200 | }, 201 | { 202 | "cell_type": "code", 203 | "execution_count": null, 204 | "metadata": { 205 | "collapsed": false 206 | }, 207 | "outputs": [], 208 | "source": [ 209 | "rgb_image = cv2.cvtColor(image, cv2.COLOR_BGR2RGB)\n", 210 | "roi = rgb_image[100:200, 100:200]\n", 211 | "plot.imshow(roi)" 212 | ] 213 | }, 214 | { 215 | "cell_type": "code", 216 | "execution_count": null, 217 | "metadata": { 218 | "collapsed": true 219 | }, 220 | "outputs": [], 221 | "source": [] 222 | } 223 | ], 224 | "metadata": { 225 | "kernelspec": { 226 | "display_name": "Python 2", 227 | "language": "python", 228 | "name": "python2" 229 | }, 230 | "language_info": { 231 | "codemirror_mode": { 232 | "name": "ipython", 233 | "version": 2 234 | }, 235 | "file_extension": ".py", 236 | "mimetype": "text/x-python", 237 | "name": "python", 238 | "nbconvert_exporter": "python", 239 | "pygments_lexer": "ipython2", 240 | "version": "2.7.12" 241 | }, 242 | "widgets": { 243 | "state": {}, 244 | "version": "1.0.0" 245 | } 246 | }, 247 | "nbformat": 4, 248 | "nbformat_minor": 0 249 | } 250 | -------------------------------------------------------------------------------- /joint_control/robot_pose_data/Left: -------------------------------------------------------------------------------- 1 | (lp0 2 | (lp1 3 | F0.004643917083740234 4 | aF-0.3619821071624756 5 | aF-1.4741320610046387 6 | aF2.142956018447876 7 | aF0.004643917083740234 8 | aF-0.11040592193603516 9 | aF-0.8713541030883789 10 | aF1.5708580017089844 11 | aF-0.6527528762817383 12 | aF0.0820302963256836 13 | aa(lp2 14 | F0.004643917083740234 15 | aF-0.3619821071624756 16 | aF-1.4741320610046387 17 | aF2.1414220333099365 18 | aF0.004643917083740234 19 | aF-0.11040592193603516 20 | aF-0.8713541030883789 21 | aF1.5708580017089844 22 | aF-0.6544981002807617 23 | aF0.0820302963256836 24 | aa(lp3 25 | F0.004643917083740234 26 | aF-0.3619821071624756 27 | aF-1.4741320610046387 28 | aF2.1414220333099365 29 | aF0.004643917083740234 30 | aF-0.11040592193603516 31 | aF-0.8713541030883789 32 | aF1.5708580017089844 33 | aF-0.6544981002807617 34 | aF0.08377552032470703 35 | aa(lp4 36 | F0.004643917083740234 37 | aF-0.3619821071624756 38 | aF-1.4741320610046387 39 | aF2.1414220333099365 40 | aF0.004643917083740234 41 | aF-0.11040592193603516 42 | aF-0.8713541030883789 43 | aF1.5708580017089844 44 | aF-0.6544981002807617 45 | aF0.08028507232666016 46 | aa(lp5 47 | F0.004643917083740234 48 | aF-0.3619821071624756 49 | aF-1.4741320610046387 50 | aF2.1414220333099365 51 | aF0.004643917083740234 52 | aF-0.11040592193603516 53 | aF-0.8713541030883789 54 | aF1.5708580017089844 55 | aF-0.6544981002807617 56 | aF0.08028507232666016 57 | aa(lp6 58 | F0.004643917083740234 59 | aF-0.3619821071624756 60 | aF-1.4741320610046387 61 | aF2.1414220333099365 62 | aF0.004643917083740234 63 | aF-0.11040592193603516 64 | aF-0.8713541030883789 65 | aF1.5708580017089844 66 | aF-0.6527528762817383 67 | aF0.08377552032470703 68 | aa(lp7 69 | F0.004643917083740234 70 | aF-0.3619821071624756 71 | aF-1.4741320610046387 72 | aF2.1414220333099365 73 | aF0.004643917083740234 74 | aF-0.11040592193603516 75 | aF-0.8713541030883789 76 | aF1.5708580017089844 77 | aF-0.6527528762817383 78 | aF0.08377552032470703 79 | aa(lp8 80 | F0.004643917083740234 81 | aF-0.3619821071624756 82 | aF-1.4741320610046387 83 | aF2.1414220333099365 84 | aF0.004643917083740234 85 | aF-0.11040592193603516 86 | aF-0.8713541030883789 87 | aF1.5708580017089844 88 | aF-0.6527528762817383 89 | aF0.08377552032470703 90 | aa(lp9 91 | F0.004643917083740234 92 | aF-0.3619821071624756 93 | aF-1.4741320610046387 94 | aF2.1414220333099365 95 | aF0.004643917083740234 96 | aF-0.11040592193603516 97 | aF-0.8713541030883789 98 | aF1.5708580017089844 99 | aF-0.6527528762817383 100 | aF0.0820302963256836 101 | aa(lp10 102 | F0.004643917083740234 103 | aF-0.3619821071624756 104 | aF-1.4741320610046387 105 | aF2.1414220333099365 106 | aF0.004643917083740234 107 | aF-0.11040592193603516 108 | aF-0.8713541030883789 109 | aF1.5708580017089844 110 | aF-0.6527528762817383 111 | aF0.0820302963256836 112 | aa(lp11 113 | F0.14730596542358398 114 | aF0.6796040534973145 115 | aF-1.4189081192016602 116 | aF-0.11202406883239746 117 | aF0.14730596542358398 118 | aF0.3697359561920166 119 | aF-0.7332940101623535 120 | aF0.052197933197021484 121 | aF-1.3997540473937988 122 | aF-0.06981325149536133 123 | aa(lp12 124 | F-0.36965203285217285 125 | aF-0.3512439727783203 126 | aF-0.29755401611328125 127 | aF-0.12889790534973145 128 | aF-0.36965203285217285 129 | aF0.1994619369506836 130 | aF0.3880600929260254 131 | aF0.04912996292114258 132 | aF-1.3892817497253418 133 | aF0.07853937149047852 134 | aa(lp13 135 | F-0.3711860179901123 136 | aF-0.3512439727783203 137 | aF-0.2990880012512207 138 | aF-0.12889790534973145 139 | aF-0.3711860179901123 140 | aF0.1994619369506836 141 | aF0.3880600929260254 142 | aF0.04912996292114258 143 | aF-1.3945178985595703 144 | aF0.07853937149047852 145 | aa(lp14 146 | F-0.3711860179901123 147 | aF-0.3512439727783203 148 | aF-0.29755401611328125 149 | aF-0.12889790534973145 150 | aF-0.3711860179901123 151 | aF0.1994619369506836 152 | aF0.3880600929260254 153 | aF0.04912996292114258 154 | aF-1.3945178985595703 155 | aF0.07155847549438477 156 | aa(lp15 157 | F0.0614018440246582 158 | aF-0.29448604583740234 159 | aF-0.09660005569458008 160 | aF-0.13196587562561035 161 | aF0.0614018440246582 162 | aF-0.11807609349489212 163 | aF0.25153398513793945 164 | aF0.047595977783203125 165 | aF-1.2915434837341309 166 | aF0.21292972564697266 167 | aa(lp16 168 | F0.05986785888671875 169 | aF-0.29448604583740234 170 | aF-0.09660005569458008 171 | aF-0.1304318904876709 172 | aF0.05986785888671875 173 | aF-0.11807609349489212 174 | aF0.25 175 | aF0.04912996292114258 176 | aF-1.281071662902832 177 | aF0.22165679931640625 178 | aa(lp17 179 | F-0.22238802909851074 180 | aF-0.22238802909851074 181 | aF-0.11654210090637207 182 | aF-0.1304318904876709 183 | aF-0.22238802909851074 184 | aF0.03992605209350586 185 | aF0.4724299907684326 186 | aF0.047595977783203125 187 | aF-1.2426743507385254 188 | aF-0.2373647689819336 189 | aa(lp18 190 | F0.0353238582611084 191 | aF-0.30675792694091797 192 | aF-0.5859460830688477 193 | aF1.4204421043395996 194 | aF0.0353238582611084 195 | aF-0.18710613250732422 196 | aF-0.4050178527832031 197 | aF1.2809319496154785 198 | aF-1.3369221687316895 199 | aF0.00698089599609375 200 | aa(lp19 201 | F0.0353238582611084 202 | aF-0.30675792694091797 203 | aF-0.5859460830688477 204 | aF1.4204421043395996 205 | aF0.0353238582611084 206 | aF-0.18710613250732422 207 | aF-0.4050178527832031 208 | aF1.2809319496154785 209 | aF-1.338667392730713 210 | aF0.0017452239990234375 211 | aa(lp20 212 | F0.0353238582611084 213 | aF-0.30675792694091797 214 | aF-0.5859460830688477 215 | aF1.4204421043395996 216 | aF0.0353238582611084 217 | aF-0.18710613250732422 218 | aF-0.4050178527832031 219 | aF1.2809319496154785 220 | aF-1.338667392730713 221 | aF0.003490447998046875 222 | aa. -------------------------------------------------------------------------------- /joint_control/robot_pose_data_json/Crouch: -------------------------------------------------------------------------------- 1 | [[0.0061779022216796875, -0.03217196464538574, -0.9970581531524658, 2.1414220333099365, 0.0061779022216796875, 0.029187917709350586, -0.995607852935791, 2.1415061950683594, -0.012217044830322266, 0.07155847549438477], [0.0061779022216796875, -0.03217196464538574, -0.9970581531524658, 2.1414220333099365, 0.0061779022216796875, 0.027653932571411133, -0.995607852935791, 2.1415061950683594, -0.012217044830322266, 0.07155847549438477], [0.0061779022216796875, -0.033705949783325195, -0.9970581531524658, 2.1414220333099365, 0.0061779022216796875, 0.027653932571411133, -0.995607852935791, 2.1415061950683594, -0.013962268829345703, 0.0733036994934082], [0.0061779022216796875, -0.033705949783325195, -0.9970581531524658, 2.142956018447876, 0.0061779022216796875, 0.027653932571411133, -0.995607852935791, 2.1415061950683594, -0.015707969665527344, 0.06981277465820312], [0.004643917083740234, -0.033705949783325195, -0.9970581531524658, 2.1414220333099365, 0.004643917083740234, 0.029187917709350586, -0.995607852935791, 2.1415061950683594, -0.013962268829345703, 0.0733036994934082], [0.0061779022216796875, -0.033705949783325195, -0.9970581531524658, 2.1414220333099365, 0.0061779022216796875, 0.027653932571411133, -0.995607852935791, 2.1415061950683594, -0.013962268829345703, 0.0733036994934082], [0.004643917083740234, -0.033705949783325195, -0.9970581531524658, 2.1414220333099365, 0.004643917083740234, 0.027653932571411133, -0.9971418380737305, 2.1415061950683594, -0.013962268829345703, 0.07155847549438477], [0.004643917083740234, -0.03217196464538574, -0.9970581531524658, 2.1414220333099365, 0.004643917083740234, 0.027653932571411133, -0.995607852935791, 2.1415061950683594, -0.013962268829345703, 0.06981277465820312], [0.0061779022216796875, -0.03217196464538574, -0.9970581531524658, 2.1414220333099365, 0.0061779022216796875, 0.027653932571411133, -0.995607852935791, 2.143040180206299, -0.013962268829345703, 0.06981277465820312], [0.004643917083740234, -0.033705949783325195, -0.9970581531524658, 2.1414220333099365, 0.004643917083740234, 0.029187917709350586, -0.9971418380737305, 2.1415061950683594, -0.015707969665527344, 0.0733036994934082], [0.004643917083740234, -0.033705949783325195, -0.9970581531524658, 2.142956018447876, 0.004643917083740234, 0.027653932571411133, -0.995607852935791, 2.1415061950683594, -0.012217044830322266, 0.06981277465820312], [0.004643917083740234, -0.033705949783325195, -0.9970581531524658, 2.1414220333099365, 0.004643917083740234, 0.027653932571411133, -0.995607852935791, 2.1415061950683594, -0.012217044830322266, 0.06981277465820312], [0.0061779022216796875, -0.033705949783325195, -0.9970581531524658, 2.1414220333099365, 0.0061779022216796875, 0.027653932571411133, -0.995607852935791, 2.1415061950683594, -0.015707969665527344, 0.06981277465820312], [0.0061779022216796875, -0.033705949783325195, -0.9970581531524658, 2.1414220333099365, 0.0061779022216796875, 0.029187917709350586, -0.995607852935791, 2.1415061950683594, -0.01745319366455078, 0.07155847549438477], [0.0061779022216796875, -0.03217196464538574, -0.9970581531524658, 2.1414220333099365, 0.0061779022216796875, 0.027653932571411133, -0.995607852935791, 2.1415061950683594, -0.013962268829345703, 0.0733036994934082], [0.0061779022216796875, -0.033705949783325195, -0.9970581531524658, 2.1414220333099365, 0.0061779022216796875, 0.029187917709350586, -0.995607852935791, 2.1415061950683594, -0.013962268829345703, 0.07155847549438477], [0.0061779022216796875, -0.033705949783325195, -0.9970581531524658, 2.1414220333099365, 0.0061779022216796875, 0.027653932571411133, -0.995607852935791, 2.1415061950683594, -0.012217044830322266, 0.07155847549438477], [0.004643917083740234, -0.03217196464538574, -0.9970581531524658, 2.1414220333099365, 0.004643917083740234, 0.029187917709350586, -0.995607852935791, 2.1415061950683594, -0.015707969665527344, 0.06981277465820312], [0.004643917083740234, -0.033705949783325195, -0.9970581531524658, 2.1414220333099365, 0.004643917083740234, 0.027653932571411133, -0.995607852935791, 2.1415061950683594, -0.013962268829345703, 0.07155847549438477], [0.004643917083740234, -0.03217196464538574, -0.9970581531524658, 2.1414220333099365, 0.004643917083740234, 0.029187917709350586, -0.995607852935791, 2.1415061950683594, -0.015707969665527344, 0.06981277465820312], [0.004643917083740234, -0.033705949783325195, -0.9970581531524658, 2.1414220333099365, 0.004643917083740234, 0.027653932571411133, -0.995607852935791, 2.1415061950683594, -0.01745319366455078, 0.0733036994934082], [0.004643917083740234, -0.033705949783325195, -0.9970581531524658, 2.1414220333099365, 0.004643917083740234, 0.029187917709350586, -0.995607852935791, 2.1415061950683594, -0.013962268829345703, 0.07504892349243164], [0.0061779022216796875, -0.033705949783325195, -0.9970581531524658, 2.1414220333099365, 0.0061779022216796875, 0.027653932571411133, -0.995607852935791, 2.1415061950683594, -0.015707969665527344, 0.0733036994934082], [0.004643917083740234, -0.033705949783325195, -0.9970581531524658, 2.1414220333099365, 0.004643917083740234, 0.027653932571411133, -0.995607852935791, 2.1415061950683594, -0.013962268829345703, 0.07504892349243164], [0.004643917083740234, -0.03217196464538574, -0.9970581531524658, 2.1414220333099365, 0.004643917083740234, 0.027653932571411133, -0.995607852935791, 2.143040180206299, -0.015707969665527344, 0.06981277465820312], [0.0061779022216796875, -0.03217196464538574, -0.9970581531524658, 2.1414220333099365, 0.0061779022216796875, 0.027653932571411133, -0.995607852935791, 2.1415061950683594, -0.013962268829345703, 0.0733036994934082], [0.004643917083740234, -0.03217196464538574, -0.9970581531524658, 2.1414220333099365, 0.004643917083740234, 0.029187917709350586, -0.995607852935791, 2.1415061950683594, -0.015707969665527344, 0.0733036994934082], [0.004643917083740234, -0.03217196464538574, -0.9970581531524658, 2.1414220333099365, 0.004643917083740234, 0.027653932571411133, -0.995607852935791, 2.1415061950683594, -0.015707969665527344, 0.06981277465820312], [0.004643917083740234, -0.033705949783325195, -0.9970581531524658, 2.1414220333099365, 0.0061779022216796875, 0.029187917709350586, -0.995607852935791, 2.1415061950683594, -0.015707969665527344, 0.07155847549438477], [0.004643917083740234, -0.033705949783325195, -0.9970581531524658, 2.1414220333099365, 0.0061779022216796875, 0.029187917709350586, -0.995607852935791, 2.1415061950683594, -0.012217044830322266, 0.06981277465820312]] -------------------------------------------------------------------------------- /joint_control/keyframes/hello.py: -------------------------------------------------------------------------------- 1 | 2 | 3 | def hello(): 4 | # Choregraphe bezier export in Python. 5 | names = list() 6 | times = list() 7 | keys = list() 8 | 9 | names.append("HeadPitch") 10 | times.append([0.80000, 1.56000, 2.24000, 2.80000, 3.48000, 4.60000]) 11 | keys.append([[0.29602, [3, -0.26667, 0.00000], [3, 0.25333, 0.00000]], [-0.17032, [3, -0.25333, 0.11200], [3, 0.22667, -0.10021]], [-0.34059, [3, -0.22667, 0.00000], [3, 0.18667, 0.00000]], [-0.05987, [3, -0.18667, 0.00000], [3, 0.22667, 0.00000]], [-0.19333, [3, -0.22667, 0.00000], [3, 0.37333, 0.00000]], [-0.01078, [3, -0.37333, 0.00000], [3, 0.00000, 0.00000]]]) 12 | 13 | names.append("HeadYaw") 14 | times.append([0.80000, 1.56000, 2.24000, 2.80000, 3.48000, 4.60000]) 15 | keys.append([[-0.13503, [3, -0.26667, 0.00000], [3, 0.25333, 0.00000]], [-0.35133, [3, -0.25333, 0.04939], [3, 0.22667, -0.04419]], [-0.41576, [3, -0.22667, 0.00372], [3, 0.18667, -0.00307]], [-0.41882, [3, -0.18667, 0.00307], [3, 0.22667, -0.00372]], [-0.52007, [3, -0.22667, 0.00000], [3, 0.37333, 0.00000]], [-0.37587, [3, -0.37333, 0.00000], [3, 0.00000, 0.00000]]]) 16 | 17 | names.append("LElbowRoll") 18 | times.append([0.72000, 1.48000, 2.16000, 2.72000, 3.40000, 4.52000]) 19 | keys.append([[-1.37902, [3, -0.24000, 0.00000], [3, 0.25333, 0.00000]], [-1.29005, [3, -0.25333, -0.03454], [3, 0.22667, 0.03091]], [-1.18267, [3, -0.22667, 0.00000], [3, 0.18667, 0.00000]], [-1.24863, [3, -0.18667, 0.02055], [3, 0.22667, -0.02496]], [-1.31920, [3, -0.22667, 0.00000], [3, 0.37333, 0.00000]], [-1.18421, [3, -0.37333, 0.00000], [3, 0.00000, 0.00000]]]) 20 | 21 | names.append("LElbowYaw") 22 | times.append([0.72000, 1.48000, 2.16000, 2.72000, 3.40000, 4.52000]) 23 | keys.append([[-0.80386, [3, -0.24000, 0.00000], [3, 0.25333, 0.00000]], [-0.69188, [3, -0.25333, -0.01372], [3, 0.22667, 0.01227]], [-0.67960, [3, -0.22667, -0.01227], [3, 0.18667, 0.01011]], [-0.61057, [3, -0.18667, 0.00000], [3, 0.22667, 0.00000]], [-0.75324, [3, -0.22667, 0.00000], [3, 0.37333, 0.00000]], [-0.67040, [3, -0.37333, 0.00000], [3, 0.00000, 0.00000]]]) 24 | 25 | names.append("LHand") 26 | times.append([1.48000, 4.52000]) 27 | keys.append([[0.00416, [3, -0.49333, 0.00000], [3, 1.01333, 0.00000]], [0.00419, [3, -1.01333, 0.00000], [3, 0.00000, 0.00000]]]) 28 | 29 | names.append("LShoulderPitch") 30 | times.append([0.72000, 1.48000, 2.16000, 2.72000, 3.40000, 4.52000]) 31 | keys.append([[1.11824, [3, -0.24000, 0.00000], [3, 0.25333, 0.00000]], [0.92803, [3, -0.25333, 0.00000], [3, 0.22667, 0.00000]], [0.94030, [3, -0.22667, 0.00000], [3, 0.18667, 0.00000]], [0.86207, [3, -0.18667, 0.00000], [3, 0.22667, 0.00000]], [0.89735, [3, -0.22667, 0.00000], [3, 0.37333, 0.00000]], [0.84212, [3, -0.37333, 0.00000], [3, 0.00000, 0.00000]]]) 32 | 33 | names.append("LShoulderRoll") 34 | times.append([0.72000, 1.48000, 2.16000, 2.72000, 3.40000, 4.52000]) 35 | keys.append([[0.36352, [3, -0.24000, 0.00000], [3, 0.25333, 0.00000]], [0.22699, [3, -0.25333, 0.02572], [3, 0.22667, -0.02301]], [0.20398, [3, -0.22667, 0.00000], [3, 0.18667, 0.00000]], [0.21779, [3, -0.18667, -0.00670], [3, 0.22667, 0.00813]], [0.24847, [3, -0.22667, 0.00000], [3, 0.37333, 0.00000]], [0.22699, [3, -0.37333, 0.00000], [3, 0.00000, 0.00000]]]) 36 | 37 | names.append("LWristYaw") 38 | times.append([1.48000, 4.52000]) 39 | keys.append([[0.14722, [3, -0.49333, 0.00000], [3, 1.01333, 0.00000]], [0.11961, [3, -1.01333, 0.00000], [3, 0.00000, 0.00000]]]) 40 | 41 | names.append("RElbowRoll") 42 | times.append([0.64000, 1.40000, 1.68000, 2.08000, 2.40000, 2.64000, 3.04000, 3.32000, 3.72000, 4.44000]) 43 | keys.append([[1.38524, [3, -0.21333, 0.00000], [3, 0.25333, 0.00000]], [0.24241, [3, -0.25333, 0.00000], [3, 0.09333, 0.00000]], [0.34907, [3, -0.09333, -0.09496], [3, 0.13333, 0.13565]], [0.93425, [3, -0.13333, 0.00000], [3, 0.10667, 0.00000]], [0.68068, [3, -0.10667, 0.14138], [3, 0.08000, -0.10604]], [0.19199, [3, -0.08000, 0.00000], [3, 0.13333, 0.00000]], [0.26180, [3, -0.13333, -0.06981], [3, 0.09333, 0.04887]], [0.70722, [3, -0.09333, -0.10397], [3, 0.13333, 0.14852]], [1.01927, [3, -0.13333, -0.06647], [3, 0.24000, 0.11965]], [1.26559, [3, -0.24000, 0.00000], [3, 0.00000, 0.00000]]]) 44 | 45 | names.append("RElbowYaw") 46 | times.append([0.64000, 1.40000, 2.08000, 2.64000, 3.32000, 3.72000, 4.44000]) 47 | keys.append([[-0.31298, [3, -0.21333, 0.00000], [3, 0.25333, 0.00000]], [0.56447, [3, -0.25333, 0.00000], [3, 0.22667, 0.00000]], [0.39113, [3, -0.22667, 0.03954], [3, 0.18667, -0.03256]], [0.34818, [3, -0.18667, 0.00000], [3, 0.22667, 0.00000]], [0.38192, [3, -0.22667, -0.03375], [3, 0.13333, 0.01985]], [0.97738, [3, -0.13333, 0.00000], [3, 0.24000, 0.00000]], [0.82678, [3, -0.24000, 0.00000], [3, 0.00000, 0.00000]]]) 48 | 49 | names.append("RHand") 50 | times.append([1.40000, 3.32000, 4.44000]) 51 | keys.append([[0.01490, [3, -0.46667, 0.00000], [3, 0.64000, 0.00000]], [0.01492, [3, -0.64000, 0.00000], [3, 0.37333, 0.00000]], [0.00742, [3, -0.37333, 0.00000], [3, 0.00000, 0.00000]]]) 52 | 53 | names.append("RShoulderPitch") 54 | times.append([0.64000, 1.40000, 2.08000, 2.64000, 3.32000, 4.44000]) 55 | keys.append([[0.24702, [3, -0.21333, 0.00000], [3, 0.25333, 0.00000]], [-1.17193, [3, -0.25333, 0.00000], [3, 0.22667, 0.00000]], [-1.08910, [3, -0.22667, 0.00000], [3, 0.18667, 0.00000]], [-1.26091, [3, -0.18667, 0.00000], [3, 0.22667, 0.00000]], [-1.14892, [3, -0.22667, -0.11198], [3, 0.37333, 0.18444]], [1.02015, [3, -0.37333, 0.00000], [3, 0.00000, 0.00000]]]) 56 | 57 | names.append("RShoulderRoll") 58 | times.append([0.64000, 1.40000, 2.08000, 2.64000, 3.32000, 4.44000]) 59 | keys.append([[-0.24241, [3, -0.21333, 0.00000], [3, 0.25333, 0.00000]], [-0.95419, [3, -0.25333, 0.00000], [3, 0.22667, 0.00000]], [-0.46024, [3, -0.22667, 0.00000], [3, 0.18667, 0.00000]], [-0.96033, [3, -0.18667, 0.00000], [3, 0.22667, 0.00000]], [-0.32832, [3, -0.22667, -0.04750], [3, 0.37333, 0.07823]], [-0.25008, [3, -0.37333, 0.00000], [3, 0.00000, 0.00000]]]) 60 | 61 | names.append("RWristYaw") 62 | times.append([1.40000, 3.32000, 4.44000]) 63 | keys.append([[-0.31298, [3, -0.46667, 0.00000], [3, 0.64000, 0.00000]], [-0.30377, [3, -0.64000, -0.00920], [3, 0.37333, 0.00537]], [0.18250, [3, -0.37333, 0.00000], [3, 0.00000, 0.00000]]]) 64 | 65 | return names, times, keys 66 | -------------------------------------------------------------------------------- /joint_control/keyframes/wipe_forehead.py: -------------------------------------------------------------------------------- 1 | 2 | 3 | def wipe_forehead(motion): 4 | # Choregraphe bezier export in Python. 5 | names = list() 6 | times = list() 7 | keys = list() 8 | 9 | names.append("HeadPitch") 10 | times.append([0.96000, 1.68000, 3.28000, 3.96000, 4.52000, 5.08000]) 11 | keys.append([[-0.02612, [3, -0.32000, 0.00000], [3, 0.24000, 0.00000]], [0.42794, [3, -0.24000, 0.00000], [3, 0.53333, 0.00000]], [0.30829, [3, -0.53333, 0.07392], [3, 0.22667, -0.03142]], [0.11194, [3, -0.22667, 0.05889], [3, 0.18667, -0.04849]], [-0.01385, [3, -0.18667, 0.00000], [3, 0.18667, 0.00000]], [0.06132, [3, -0.18667, 0.00000], [3, 0.00000, 0.00000]]]) 12 | 13 | names.append("HeadYaw") 14 | times.append([0.96000, 1.68000, 3.28000, 3.96000, 4.52000, 5.08000]) 15 | keys.append([[-0.23474, [3, -0.32000, 0.00000], [3, 0.24000, 0.00000]], [-0.62285, [3, -0.24000, 0.00000], [3, 0.53333, 0.00000]], [-0.11356, [3, -0.53333, -0.14425], [3, 0.22667, 0.06131]], [-0.00618, [3, -0.22667, 0.00000], [3, 0.18667, 0.00000]], [-0.02765, [3, -0.18667, 0.00511], [3, 0.18667, -0.00511]], [-0.03686, [3, -0.18667, 0.00000], [3, 0.00000, 0.00000]]]) 16 | 17 | names.append("LElbowRoll") 18 | times.append([0.80000, 1.52000, 3.12000, 3.80000, 4.36000, 4.92000]) 19 | keys.append([[-0.86667, [3, -0.26667, 0.00000], [3, 0.24000, 0.00000]], [-0.86820, [3, -0.24000, 0.00000], [3, 0.53333, 0.00000]], [-0.82218, [3, -0.53333, 0.00000], [3, 0.22667, 0.00000]], [-0.99246, [3, -0.22667, 0.00000], [3, 0.18667, 0.00000]], [-0.96638, [3, -0.18667, 0.00000], [3, 0.18667, 0.00000]], [-0.99092, [3, -0.18667, 0.00000], [3, 0.00000, 0.00000]]]) 20 | 21 | names.append("LElbowYaw") 22 | times.append([0.80000, 1.52000, 3.12000, 3.80000, 4.36000, 4.92000]) 23 | keys.append([[-0.95726, [3, -0.26667, 0.00000], [3, 0.24000, 0.00000]], [-0.82380, [3, -0.24000, 0.00000], [3, 0.53333, 0.00000]], [-1.00788, [3, -0.53333, 0.00000], [3, 0.22667, 0.00000]], [-0.92504, [3, -0.22667, 0.00000], [3, 0.18667, 0.00000]], [-1.24412, [3, -0.18667, 0.00000], [3, 0.18667, 0.00000]], [-0.96033, [3, -0.18667, 0.00000], [3, 0.00000, 0.00000]]]) 24 | 25 | names.append("LHand") 26 | times.append([1.52000, 3.12000, 3.80000, 4.92000]) 27 | keys.append([[0.00230, [3, -0.50667, 0.00000], [3, 0.53333, 0.00000]], [0.00230, [3, -0.53333, 0.00000], [3, 0.22667, 0.00000]], [0.00230, [3, -0.22667, 0.00000], [3, 0.37333, 0.00000]], [0.00230, [3, -0.37333, 0.00000], [3, 0.00000, 0.00000]]]) 28 | 29 | names.append("LShoulderPitch") 30 | times.append([0.80000, 1.52000, 3.12000, 3.80000, 4.36000, 4.92000]) 31 | keys.append([[0.86360, [3, -0.26667, 0.00000], [3, 0.24000, 0.00000]], [0.85900, [3, -0.24000, 0.00000], [3, 0.53333, 0.00000]], [0.88814, [3, -0.53333, -0.01651], [3, 0.22667, 0.00702]], [0.92956, [3, -0.22667, -0.02355], [3, 0.18667, 0.01940]], [1.01700, [3, -0.18667, 0.00000], [3, 0.18667, 0.00000]], [0.97712, [3, -0.18667, 0.00000], [3, 0.00000, 0.00000]]]) 32 | 33 | names.append("LShoulderRoll") 34 | times.append([0.80000, 1.52000, 3.12000, 3.80000, 4.36000, 4.92000]) 35 | keys.append([[0.28682, [3, -0.26667, 0.00000], [3, 0.24000, 0.00000]], [0.23006, [3, -0.24000, 0.00873], [3, 0.53333, -0.01940]], [0.20245, [3, -0.53333, 0.00000], [3, 0.22667, 0.00000]], [0.40647, [3, -0.22667, 0.00000], [3, 0.18667, 0.00000]], [0.36045, [3, -0.18667, 0.01457], [3, 0.18667, -0.01457]], [0.31903, [3, -0.18667, 0.00000], [3, 0.00000, 0.00000]]]) 36 | 37 | names.append("LWristYaw") 38 | times.append([1.52000, 3.12000, 3.80000, 4.92000]) 39 | keys.append([[0.38653, [3, -0.50667, 0.00000], [3, 0.53333, 0.00000]], [0.38653, [3, -0.53333, 0.00000], [3, 0.22667, 0.00000]], [0.38653, [3, -0.22667, 0.00000], [3, 0.37333, 0.00000]], [0.38653, [3, -0.37333, 0.00000], [3, 0.00000, 0.00000]]]) 40 | 41 | names.append("RElbowRoll") 42 | times.append([0.64000, 1.36000, 2.96000, 3.64000, 4.20000, 4.76000]) 43 | keys.append([[1.28093, [3, -0.21333, 0.00000], [3, 0.24000, 0.00000]], [1.39752, [3, -0.24000, -0.03015], [3, 0.53333, 0.06700]], [1.57239, [3, -0.53333, 0.00000], [3, 0.22667, 0.00000]], [1.24105, [3, -0.22667, 0.01863], [3, 0.18667, -0.01534]], [1.22571, [3, -0.18667, 0.01534], [3, 0.18667, -0.01534]], [0.84067, [3, -0.18667, 0.00000], [3, 0.00000, 0.00000]]]) 44 | 45 | names.append("RElbowYaw") 46 | times.append([0.64000, 1.36000, 2.96000, 3.64000, 4.20000, 4.76000]) 47 | keys.append([[-0.12890, [3, -0.21333, 0.00000], [3, 0.24000, 0.00000]], [-0.28537, [3, -0.24000, 0.00000], [3, 0.53333, 0.00000]], [-0.15651, [3, -0.53333, -0.12886], [3, 0.22667, 0.05476]], [0.75469, [3, -0.22667, -0.24283], [3, 0.18667, 0.19998]], [1.17193, [3, -0.18667, 0.00000], [3, 0.18667, 0.00000]], [0.67799, [3, -0.18667, 0.00000], [3, 0.00000, 0.00000]]]) 48 | 49 | names.append("RHand") 50 | times.append([1.36000, 2.96000, 3.64000, 4.76000]) 51 | keys.append([[0.00291, [3, -0.45333, 0.00000], [3, 0.53333, 0.00000]], [0.00290, [3, -0.53333, 0.00000], [3, 0.22667, 0.00000]], [0.00291, [3, -0.22667, 0.00000], [3, 0.37333, 0.00000]], [0.00290, [3, -0.37333, 0.00000], [3, 0.00000, 0.00000]]]) 52 | 53 | names.append("RShoulderPitch") 54 | times.append([0.64000, 1.36000, 2.96000, 3.64000, 4.20000, 4.76000]) 55 | keys.append([[0.07674, [3, -0.21333, 0.00000], [3, 0.24000, 0.00000]], [-0.59515, [3, -0.24000, 0.09759], [3, 0.53333, -0.21688]], [-0.86667, [3, -0.53333, 0.00000], [3, 0.22667, 0.00000]], [-0.61356, [3, -0.22667, -0.25311], [3, 0.18667, 0.20844]], [0.58450, [3, -0.18667, -0.24927], [3, 0.18667, 0.24927]], [0.88209, [3, -0.18667, 0.00000], [3, 0.00000, 0.00000]]]) 56 | 57 | names.append("RShoulderRoll") 58 | times.append([0.64000, 1.36000, 2.96000, 3.64000, 4.20000, 4.76000]) 59 | keys.append([[-0.01998, [3, -0.21333, 0.00000], [3, 0.24000, 0.00000]], [-0.01998, [3, -0.24000, 0.00000], [3, 0.53333, 0.00000]], [-0.61518, [3, -0.53333, 0.19018], [3, 0.22667, -0.08083]], [-0.83300, [3, -0.22667, 0.00000], [3, 0.18667, 0.00000]], [-0.22401, [3, -0.18667, -0.00920], [3, 0.18667, 0.00920]], [-0.21480, [3, -0.18667, 0.00000], [3, 0.00000, 0.00000]]]) 60 | 61 | names.append("RWristYaw") 62 | times.append([1.36000, 2.96000, 3.64000, 4.76000]) 63 | keys.append([[-0.05833, [3, -0.45333, 0.00000], [3, 0.53333, 0.00000]], [-0.05220, [3, -0.53333, 0.00000], [3, 0.22667, 0.00000]], [-0.06754, [3, -0.22667, 0.00000], [3, 0.37333, 0.00000]], [-0.03839, [3, -0.37333, 0.00000], [3, 0.00000, 0.00000]]]) 64 | 65 | return names, times, keys 66 | -------------------------------------------------------------------------------- /joint_control/robot_pose_data/Sit: -------------------------------------------------------------------------------- 1 | (lp0 2 | (lp1 3 | F-0.7562201023101807 4 | aF0.7839159965515137 5 | aF-1.630600094795227 6 | aF0.2607381343841553 7 | aF-0.7562201023101807 8 | aF0.09975194931030273 9 | aF-1.5708580017089844 10 | aF0.1074218824505806 11 | aF-0.03839683532714844 12 | aF0.438077449798584 13 | aa(lp2 14 | F-0.7562201023101807 15 | aF0.7839159965515137 16 | aF-1.630600094795227 17 | aF0.2607381343841553 18 | aF-0.7562201023101807 19 | aF0.09975194931030273 20 | aF-1.5708580017089844 21 | aF0.1074218824505806 22 | aF-0.036651611328125 23 | aF0.438077449798584 24 | aa(lp3 25 | F-0.7562201023101807 26 | aF0.7839159965515137 27 | aF-1.630600094795227 28 | aF0.2607381343841553 29 | aF-0.7562201023101807 30 | aF0.09821796417236328 31 | aF-1.5708580017089844 32 | aF0.1074218824505806 33 | aF-0.036651611328125 34 | aF0.43633222579956055 35 | aa(lp4 36 | F-0.7562201023101807 37 | aF0.7823820114135742 38 | aF-1.630600094795227 39 | aF0.2607381343841553 40 | aF-0.7562201023101807 41 | aF0.09975194931030273 42 | aF-1.5708580017089844 43 | aF0.1074218824505806 44 | aF-0.03839683532714844 45 | aF0.44156789779663086 46 | aa(lp5 47 | F-0.7562201023101807 48 | aF0.7839159965515137 49 | aF-1.630600094795227 50 | aF0.2607381343841553 51 | aF-0.7562201023101807 52 | aF0.09975194931030273 53 | aF-1.5708580017089844 54 | aF0.1074218824505806 55 | aF-0.03839683532714844 56 | aF0.4398226737976074 57 | aa(lp6 58 | F-0.7562201023101807 59 | aF0.7839159965515137 60 | aF-1.630600094795227 61 | aF0.2607381343841553 62 | aF-0.7562201023101807 63 | aF0.09821796417236328 64 | aF-1.5708580017089844 65 | aF0.1074218824505806 66 | aF-0.03839683532714844 67 | aF0.438077449798584 68 | aa(lp7 69 | F-0.7562201023101807 70 | aF0.7823820114135742 71 | aF-1.630600094795227 72 | aF0.2607381343841553 73 | aF-0.7562201023101807 74 | aF0.09975194931030273 75 | aF-1.5708580017089844 76 | aF0.1074218824505806 77 | aF-0.03839683532714844 78 | aF0.44156789779663086 79 | aa(lp8 80 | F-0.7562201023101807 81 | aF0.7823820114135742 82 | aF-1.630600094795227 83 | aF0.2607381343841553 84 | aF-0.7562201023101807 85 | aF0.09975194931030273 86 | aF-1.5708580017089844 87 | aF0.1074218824505806 88 | aF-0.03839683532714844 89 | aF0.4398226737976074 90 | aa(lp9 91 | F-0.7562201023101807 92 | aF0.7839159965515137 93 | aF-1.630600094795227 94 | aF0.2607381343841553 95 | aF-0.7562201023101807 96 | aF0.09975194931030273 97 | aF-1.5708580017089844 98 | aF0.1074218824505806 99 | aF-0.03839683532714844 100 | aF0.4398226737976074 101 | aa(lp10 102 | F-0.7562201023101807 103 | aF0.7839159965515137 104 | aF-1.630600094795227 105 | aF0.2607381343841553 106 | aF-0.7562201023101807 107 | aF0.09821796417236328 108 | aF-1.5708580017089844 109 | aF0.1074218824505806 110 | aF-0.03839683532714844 111 | aF0.43633222579956055 112 | aa(lp11 113 | F-0.7562201023101807 114 | aF0.7823820114135742 115 | aF-1.630600094795227 116 | aF0.2607381343841553 117 | aF-0.7562201023101807 118 | aF0.09821796417236328 119 | aF-1.5708580017089844 120 | aF0.1074218824505806 121 | aF-0.03839683532714844 122 | aF0.43284130096435547 123 | aa(lp12 124 | F-0.7562201023101807 125 | aF0.7823820114135742 126 | aF-1.630600094795227 127 | aF0.2607381343841553 128 | aF-0.7562201023101807 129 | aF0.09975194931030273 130 | aF-1.569324016571045 131 | aF0.1074218824505806 132 | aF-0.041887760162353516 133 | aF0.438077449798584 134 | aa(lp13 135 | F-0.7562201023101807 136 | aF0.7839159965515137 137 | aF-1.630600094795227 138 | aF0.2607381343841553 139 | aF-0.7562201023101807 140 | aF0.09821796417236328 141 | aF-1.569324016571045 142 | aF0.1074218824505806 143 | aF-0.041887760162353516 144 | aF0.43284130096435547 145 | aa(lp14 146 | F-0.7562201023101807 147 | aF0.7823820114135742 148 | aF-1.630600094795227 149 | aF0.2607381343841553 150 | aF-0.7562201023101807 151 | aF0.09975194931030273 152 | aF-1.5708580017089844 153 | aF0.1074218824505806 154 | aF-0.04014253616333008 155 | aF0.4345865249633789 156 | aa(lp15 157 | F-0.7577540874481201 158 | aF0.7839159965515137 159 | aF-1.630600094795227 160 | aF0.2607381343841553 161 | aF-0.7577540874481201 162 | aF0.09975194931030273 163 | aF-1.5708580017089844 164 | aF0.1074218824505806 165 | aF-0.04014253616333008 166 | aF0.43633222579956055 167 | aa(lp16 168 | F-0.7562201023101807 169 | aF0.7823820114135742 170 | aF-1.630600094795227 171 | aF0.2607381343841553 172 | aF-0.7562201023101807 173 | aF0.09821796417236328 174 | aF-1.5708580017089844 175 | aF0.1074218824505806 176 | aF-0.04014253616333008 177 | aF0.438077449798584 178 | aa(lp17 179 | F-0.7562201023101807 180 | aF0.7823820114135742 181 | aF-1.630600094795227 182 | aF0.2607381343841553 183 | aF-0.7562201023101807 184 | aF0.09821796417236328 185 | aF-1.5708580017089844 186 | aF0.1074218824505806 187 | aF-0.041887760162353516 188 | aF0.43284130096435547 189 | aa(lp18 190 | F-0.7577540874481201 191 | aF0.7839159965515137 192 | aF-1.630600094795227 193 | aF0.2607381343841553 194 | aF-0.7577540874481201 195 | aF0.09975194931030273 196 | aF-1.5708580017089844 197 | aF0.1074218824505806 198 | aF-0.03839683532714844 199 | aF0.4345865249633789 200 | aa(lp19 201 | F-0.7562201023101807 202 | aF0.7823820114135742 203 | aF-1.630600094795227 204 | aF0.2607381343841553 205 | aF-0.7562201023101807 206 | aF0.09821796417236328 207 | aF-1.5708580017089844 208 | aF0.1074218824505806 209 | aF-0.041887760162353516 210 | aF0.4345865249633789 211 | aa(lp20 212 | F-0.6595780849456787 213 | aF0.1595778465270996 214 | aF-1.5354920625686646 215 | aF1.5201520919799805 216 | aF-0.6595780849456787 217 | aF-0.06131792068481445 218 | aF-1.4665460586547852 219 | aF1.3607001304626465 220 | aF-0.013962268829345703 221 | aF-0.34906625747680664 222 | aa(lp21 223 | F-0.6595780849456787 224 | aF0.1595778465270996 225 | aF-1.5354920625686646 226 | aF1.5201520919799805 227 | aF-0.6595780849456787 228 | aF-0.06131792068481445 229 | aF-1.4665460586547852 230 | aF1.3607001304626465 231 | aF-0.012217044830322266 232 | aF-0.34906625747680664 233 | aa(lp22 234 | F-0.6595780849456787 235 | aF0.1595778465270996 236 | aF-1.5354920625686646 237 | aF1.5201520919799805 238 | aF-0.6595780849456787 239 | aF-0.06131792068481445 240 | aF-1.4665460586547852 241 | aF1.3607001304626465 242 | aF-0.012217044830322266 243 | aF-0.3508114814758301 244 | aa(lp23 245 | F-0.6503739356994629 246 | aF-0.3052239418029785 247 | aF-0.91115403175354 248 | aF0.34050607681274414 249 | aF-0.6503739356994629 250 | aF-0.0030260086059570312 251 | aF-0.8606162071228027 252 | aF0.14117002487182617 253 | aF-0.003490447998046875 254 | aF-0.4066619873046875 255 | aa(lp24 256 | F-0.6503739356994629 257 | aF-0.3052239418029785 258 | aF-0.91115403175354 259 | aF0.34050607681274414 260 | aF-0.6503739356994629 261 | aF-0.0030260086059570312 262 | aF-0.8606162071228027 263 | aF0.14117002487182617 264 | aF-0.0052356719970703125 265 | aF-0.411898136138916 266 | aa(lp25 267 | F-0.98785400390625 268 | aF-0.3803901672363281 269 | aF-0.5383920669555664 270 | aF0.28374814987182617 271 | aF-0.98785400390625 272 | aF0.36820197105407715 273 | aF-0.6059720516204834 274 | aF0.4326300621032715 275 | aF0.04188823699951172 276 | aF-0.41364336013793945 277 | aa(lp26 278 | F-0.3128941059112549 279 | aF-0.230057954788208 280 | aF-1.6704840660095215 281 | aF0.9663779735565186 282 | aF-0.3128941059112549 283 | aF0.0353238582611084 284 | aF-1.6228026151657104 285 | aF0.8299360275268555 286 | aF0.025310691446065903 287 | aF-0.16758745908737183 288 | aa. -------------------------------------------------------------------------------- /software_installation/sexpr.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | ## 3 | ## sexpr.py - by Yusuke Shinyama 4 | ## 5 | ## * public domain * 6 | ## 7 | try: 8 | import future 9 | except: 10 | # future is here if missing :) 11 | pass 12 | 13 | ## AbstractFilter 14 | ## 15 | class AbstractFilter: 16 | def __init__(self, next_filter): 17 | self.next_filter = next_filter 18 | return 19 | 20 | def process(self, s): 21 | raise NotImplementedError 22 | 23 | def feed(self, s): 24 | self.feed_next(self.process(s)) 25 | return 26 | 27 | def feed_next(self, s): 28 | self.next_filter.feed(s) 29 | return 30 | 31 | def close(self): 32 | self.next_filter.close() 33 | return 34 | 35 | 36 | ## AbstractConsumer 37 | ## 38 | class AbstractConsumer: 39 | def feed(self, s): 40 | raise NotImplementedError 41 | 42 | def close(self): 43 | return 44 | 45 | 46 | ## SExprReader 47 | ## 48 | class SExprReader(AbstractFilter): 49 | """Usage: 50 | reader = SExprReader(consumer) 51 | reader.feed("(this is (sexpr))") 52 | reader.close() 53 | """ 54 | 55 | COMMENT_BEGIN = ";" 56 | COMMENT_END = "\n" 57 | SEPARATOR = " \t\n" 58 | PAREN_BEGIN = "(" 59 | PAREN_END = ")" 60 | QUOTE = '"' 61 | ESCAPE = "\\" 62 | 63 | def __init__(self, next_filter, 64 | comment_begin=COMMENT_BEGIN, 65 | comment_end=COMMENT_END, 66 | separator=SEPARATOR, 67 | paren_begin=PAREN_BEGIN, 68 | paren_end=PAREN_END, 69 | quote=QUOTE, 70 | escape=ESCAPE): 71 | AbstractFilter.__init__(self, next_filter) 72 | self.comment_begin = comment_begin 73 | self.comment_end = comment_end 74 | self.separator = separator 75 | self.paren_begin = paren_begin 76 | self.paren_end = paren_end 77 | self.quote = quote 78 | self.escape = escape 79 | self.special = comment_begin + separator + paren_begin + paren_end + quote + escape 80 | self.reset() 81 | 82 | # SExprReader ignores any error and 83 | # try to continue as long as possible. 84 | # if you want to throw exception however, 85 | # please modify these methods. 86 | 87 | # called if redundant parantheses are found. 88 | def illegal_close_paren(self, i): 89 | print("Ignore a close parenthesis: %d" % i) 90 | 91 | # called if it reaches the end-of-file while the stack is not empty. 92 | def premature_eof(self, i, x): 93 | print("Premature end of file: %d parens left, partial=%s" % (i, x)) 94 | 95 | # reset the internal states. 96 | def reset(self): 97 | self.incomment = False # if within a comment. 98 | self.inquote = False # if within a quote. 99 | self.inescape = False # if within a escape. 100 | self.sym = '' # partially constructed symbol. 101 | # NOTICE: None != nil (an empty list) 102 | self.build = None # partially constructed list. 103 | self.build_stack = [] # to store a chain of partial lists. 104 | return self 105 | 106 | # analyze strings 107 | def feed(self, tokens): 108 | for (i, c) in enumerate(tokens): 109 | if self.incomment: 110 | # within a comment - skip 111 | self.incomment = (c not in self.comment_end) 112 | elif self.inescape or (c not in self.special): 113 | # add to the current working symbol 114 | self.sym += c 115 | self.inescape = False 116 | elif c in self.escape: 117 | # escape 118 | self.inescape = True 119 | elif self.inquote and (c not in self.quote): 120 | self.sym += c 121 | else: 122 | # special character (blanks, parentheses, or comment) 123 | if self.sym: 124 | # close the current symbol 125 | if self.build is None: 126 | self.feed_next(self.sym) 127 | else: 128 | self.build.append(self.sym) 129 | self.sym = '' 130 | if c in self.comment_begin: 131 | # comment 132 | self.incomment = True 133 | elif c in self.quote: 134 | # quote 135 | self.inquote = not self.inquote 136 | elif c in self.paren_begin: 137 | # beginning a new list. 138 | self.build_stack.append(self.build) 139 | empty = [] 140 | if self.build is None: 141 | # begin from a scratch. 142 | self.build = empty 143 | else: 144 | # begin from the end of the current list. 145 | self.build.append(empty) 146 | self.build = empty 147 | elif c in self.paren_end: 148 | # terminating the current list 149 | if self.build is None: 150 | # there must be a working list. 151 | self.illegal_close_paren(i) 152 | else: 153 | if len(self.build_stack) == 1: 154 | # current working list is the last one in the stack. 155 | self.feed_next(self.build) 156 | self.build = self.build_stack.pop() 157 | return self 158 | 159 | # terminate 160 | def terminate(self): 161 | # a working list should not exist. 162 | if self.build is not None: 163 | # error - still try to construct a partial structure. 164 | if self.sym: 165 | self.build.append(self.sym) 166 | self.sym = '' 167 | if len(self.build_stack) == 1: 168 | x = self.build 169 | else: 170 | x = self.build_stack[1] 171 | self.build = None 172 | self.build_stack = [] 173 | self.premature_eof(len(self.build_stack), x) 174 | elif self.sym: 175 | # flush the current working symbol. 176 | self.feed_next(self.sym) 177 | self.sym = '' 178 | return self 179 | 180 | # closing. 181 | def close(self): 182 | AbstractFilter.close(self) 183 | self.terminate() 184 | 185 | 186 | ## StrictSExprReader 187 | ## 188 | class SExprIllegalClosingParenError(ValueError): 189 | """It throws an exception with an ill-structured input.""" 190 | pass 191 | 192 | 193 | class SExprPrematureEOFError(ValueError): 194 | pass 195 | 196 | 197 | class StrictSExprReader(SExprReader): 198 | def illegal_close_paren(self, i): 199 | raise SExprIllegalClosingParenError(i) 200 | 201 | def premature_eof(self, i, x): 202 | raise SExprPrematureEOFError(i, x) 203 | 204 | 205 | ## str2sexpr 206 | ## 207 | class _SExprStrConverter(AbstractConsumer): 208 | results = [] 209 | 210 | def feed(self, s): 211 | _SExprStrConverter.results.append(s) 212 | 213 | 214 | _str_converter = SExprReader(_SExprStrConverter()) 215 | _str_converter_strict = StrictSExprReader(_SExprStrConverter()) 216 | 217 | 218 | def str2sexpr(s): 219 | """parse a string as a sexpr.""" 220 | _SExprStrConverter.results = [] 221 | _str_converter.reset().feed(s).terminate() 222 | return _SExprStrConverter.results 223 | 224 | 225 | def str2sexpr_strict(s): 226 | """parse a string as a sexpr.""" 227 | _SExprStrConverter.results = [] 228 | _str_converter_strict.reset().feed(s).terminate() 229 | return _SExprStrConverter.results 230 | 231 | 232 | ## sexpr2str 233 | ## 234 | def sexpr2str(e): 235 | """convert a sexpr into Lisp-like representation.""" 236 | if not isinstance(e, list): 237 | return e 238 | return "(" + " ".join(map(sexpr2str, e)) + ")" 239 | -------------------------------------------------------------------------------- /joint_control/robot_pose_data/Crouch: -------------------------------------------------------------------------------- 1 | (lp0 2 | (lp1 3 | F0.0061779022216796875 4 | aF-0.03217196464538574 5 | aF-0.9970581531524658 6 | aF2.1414220333099365 7 | aF0.0061779022216796875 8 | aF0.029187917709350586 9 | aF-0.995607852935791 10 | aF2.1415061950683594 11 | aF-0.012217044830322266 12 | aF0.07155847549438477 13 | aa(lp2 14 | F0.0061779022216796875 15 | aF-0.03217196464538574 16 | aF-0.9970581531524658 17 | aF2.1414220333099365 18 | aF0.0061779022216796875 19 | aF0.027653932571411133 20 | aF-0.995607852935791 21 | aF2.1415061950683594 22 | aF-0.012217044830322266 23 | aF0.07155847549438477 24 | aa(lp3 25 | F0.0061779022216796875 26 | aF-0.033705949783325195 27 | aF-0.9970581531524658 28 | aF2.1414220333099365 29 | aF0.0061779022216796875 30 | aF0.027653932571411133 31 | aF-0.995607852935791 32 | aF2.1415061950683594 33 | aF-0.013962268829345703 34 | aF0.0733036994934082 35 | aa(lp4 36 | F0.0061779022216796875 37 | aF-0.033705949783325195 38 | aF-0.9970581531524658 39 | aF2.142956018447876 40 | aF0.0061779022216796875 41 | aF0.027653932571411133 42 | aF-0.995607852935791 43 | aF2.1415061950683594 44 | aF-0.015707969665527344 45 | aF0.06981277465820312 46 | aa(lp5 47 | F0.004643917083740234 48 | aF-0.033705949783325195 49 | aF-0.9970581531524658 50 | aF2.1414220333099365 51 | aF0.004643917083740234 52 | aF0.029187917709350586 53 | aF-0.995607852935791 54 | aF2.1415061950683594 55 | aF-0.013962268829345703 56 | aF0.0733036994934082 57 | aa(lp6 58 | F0.0061779022216796875 59 | aF-0.033705949783325195 60 | aF-0.9970581531524658 61 | aF2.1414220333099365 62 | aF0.0061779022216796875 63 | aF0.027653932571411133 64 | aF-0.995607852935791 65 | aF2.1415061950683594 66 | aF-0.013962268829345703 67 | aF0.0733036994934082 68 | aa(lp7 69 | F0.004643917083740234 70 | aF-0.033705949783325195 71 | aF-0.9970581531524658 72 | aF2.1414220333099365 73 | aF0.004643917083740234 74 | aF0.027653932571411133 75 | aF-0.9971418380737305 76 | aF2.1415061950683594 77 | aF-0.013962268829345703 78 | aF0.07155847549438477 79 | aa(lp8 80 | F0.004643917083740234 81 | aF-0.03217196464538574 82 | aF-0.9970581531524658 83 | aF2.1414220333099365 84 | aF0.004643917083740234 85 | aF0.027653932571411133 86 | aF-0.995607852935791 87 | aF2.1415061950683594 88 | aF-0.013962268829345703 89 | aF0.06981277465820312 90 | aa(lp9 91 | F0.0061779022216796875 92 | aF-0.03217196464538574 93 | aF-0.9970581531524658 94 | aF2.1414220333099365 95 | aF0.0061779022216796875 96 | aF0.027653932571411133 97 | aF-0.995607852935791 98 | aF2.143040180206299 99 | aF-0.013962268829345703 100 | aF0.06981277465820312 101 | aa(lp10 102 | F0.004643917083740234 103 | aF-0.033705949783325195 104 | aF-0.9970581531524658 105 | aF2.1414220333099365 106 | aF0.004643917083740234 107 | aF0.029187917709350586 108 | aF-0.9971418380737305 109 | aF2.1415061950683594 110 | aF-0.015707969665527344 111 | aF0.0733036994934082 112 | aa(lp11 113 | F0.004643917083740234 114 | aF-0.033705949783325195 115 | aF-0.9970581531524658 116 | aF2.142956018447876 117 | aF0.004643917083740234 118 | aF0.027653932571411133 119 | aF-0.995607852935791 120 | aF2.1415061950683594 121 | aF-0.012217044830322266 122 | aF0.06981277465820312 123 | aa(lp12 124 | F0.004643917083740234 125 | aF-0.033705949783325195 126 | aF-0.9970581531524658 127 | aF2.1414220333099365 128 | aF0.004643917083740234 129 | aF0.027653932571411133 130 | aF-0.995607852935791 131 | aF2.1415061950683594 132 | aF-0.012217044830322266 133 | aF0.06981277465820312 134 | aa(lp13 135 | F0.0061779022216796875 136 | aF-0.033705949783325195 137 | aF-0.9970581531524658 138 | aF2.1414220333099365 139 | aF0.0061779022216796875 140 | aF0.027653932571411133 141 | aF-0.995607852935791 142 | aF2.1415061950683594 143 | aF-0.015707969665527344 144 | aF0.06981277465820312 145 | aa(lp14 146 | F0.0061779022216796875 147 | aF-0.033705949783325195 148 | aF-0.9970581531524658 149 | aF2.1414220333099365 150 | aF0.0061779022216796875 151 | aF0.029187917709350586 152 | aF-0.995607852935791 153 | aF2.1415061950683594 154 | aF-0.01745319366455078 155 | aF0.07155847549438477 156 | aa(lp15 157 | F0.0061779022216796875 158 | aF-0.03217196464538574 159 | aF-0.9970581531524658 160 | aF2.1414220333099365 161 | aF0.0061779022216796875 162 | aF0.027653932571411133 163 | aF-0.995607852935791 164 | aF2.1415061950683594 165 | aF-0.013962268829345703 166 | aF0.0733036994934082 167 | aa(lp16 168 | F0.0061779022216796875 169 | aF-0.033705949783325195 170 | aF-0.9970581531524658 171 | aF2.1414220333099365 172 | aF0.0061779022216796875 173 | aF0.029187917709350586 174 | aF-0.995607852935791 175 | aF2.1415061950683594 176 | aF-0.013962268829345703 177 | aF0.07155847549438477 178 | aa(lp17 179 | F0.0061779022216796875 180 | aF-0.033705949783325195 181 | aF-0.9970581531524658 182 | aF2.1414220333099365 183 | aF0.0061779022216796875 184 | aF0.027653932571411133 185 | aF-0.995607852935791 186 | aF2.1415061950683594 187 | aF-0.012217044830322266 188 | aF0.07155847549438477 189 | aa(lp18 190 | F0.004643917083740234 191 | aF-0.03217196464538574 192 | aF-0.9970581531524658 193 | aF2.1414220333099365 194 | aF0.004643917083740234 195 | aF0.029187917709350586 196 | aF-0.995607852935791 197 | aF2.1415061950683594 198 | aF-0.015707969665527344 199 | aF0.06981277465820312 200 | aa(lp19 201 | F0.004643917083740234 202 | aF-0.033705949783325195 203 | aF-0.9970581531524658 204 | aF2.1414220333099365 205 | aF0.004643917083740234 206 | aF0.027653932571411133 207 | aF-0.995607852935791 208 | aF2.1415061950683594 209 | aF-0.013962268829345703 210 | aF0.07155847549438477 211 | aa(lp20 212 | F0.004643917083740234 213 | aF-0.03217196464538574 214 | aF-0.9970581531524658 215 | aF2.1414220333099365 216 | aF0.004643917083740234 217 | aF0.029187917709350586 218 | aF-0.995607852935791 219 | aF2.1415061950683594 220 | aF-0.015707969665527344 221 | aF0.06981277465820312 222 | aa(lp21 223 | F0.004643917083740234 224 | aF-0.033705949783325195 225 | aF-0.9970581531524658 226 | aF2.1414220333099365 227 | aF0.004643917083740234 228 | aF0.027653932571411133 229 | aF-0.995607852935791 230 | aF2.1415061950683594 231 | aF-0.01745319366455078 232 | aF0.0733036994934082 233 | aa(lp22 234 | F0.004643917083740234 235 | aF-0.033705949783325195 236 | aF-0.9970581531524658 237 | aF2.1414220333099365 238 | aF0.004643917083740234 239 | aF0.029187917709350586 240 | aF-0.995607852935791 241 | aF2.1415061950683594 242 | aF-0.013962268829345703 243 | aF0.07504892349243164 244 | aa(lp23 245 | F0.0061779022216796875 246 | aF-0.033705949783325195 247 | aF-0.9970581531524658 248 | aF2.1414220333099365 249 | aF0.0061779022216796875 250 | aF0.027653932571411133 251 | aF-0.995607852935791 252 | aF2.1415061950683594 253 | aF-0.015707969665527344 254 | aF0.0733036994934082 255 | aa(lp24 256 | F0.004643917083740234 257 | aF-0.033705949783325195 258 | aF-0.9970581531524658 259 | aF2.1414220333099365 260 | aF0.004643917083740234 261 | aF0.027653932571411133 262 | aF-0.995607852935791 263 | aF2.1415061950683594 264 | aF-0.013962268829345703 265 | aF0.07504892349243164 266 | aa(lp25 267 | F0.004643917083740234 268 | aF-0.03217196464538574 269 | aF-0.9970581531524658 270 | aF2.1414220333099365 271 | aF0.004643917083740234 272 | aF0.027653932571411133 273 | aF-0.995607852935791 274 | aF2.143040180206299 275 | aF-0.015707969665527344 276 | aF0.06981277465820312 277 | aa(lp26 278 | F0.0061779022216796875 279 | aF-0.03217196464538574 280 | aF-0.9970581531524658 281 | aF2.1414220333099365 282 | aF0.0061779022216796875 283 | aF0.027653932571411133 284 | aF-0.995607852935791 285 | aF2.1415061950683594 286 | aF-0.013962268829345703 287 | aF0.0733036994934082 288 | aa(lp27 289 | F0.004643917083740234 290 | aF-0.03217196464538574 291 | aF-0.9970581531524658 292 | aF2.1414220333099365 293 | aF0.004643917083740234 294 | aF0.029187917709350586 295 | aF-0.995607852935791 296 | aF2.1415061950683594 297 | aF-0.015707969665527344 298 | aF0.0733036994934082 299 | aa(lp28 300 | F0.004643917083740234 301 | aF-0.03217196464538574 302 | aF-0.9970581531524658 303 | aF2.1414220333099365 304 | aF0.004643917083740234 305 | aF0.027653932571411133 306 | aF-0.995607852935791 307 | aF2.1415061950683594 308 | aF-0.015707969665527344 309 | aF0.06981277465820312 310 | aa(lp29 311 | F0.004643917083740234 312 | aF-0.033705949783325195 313 | aF-0.9970581531524658 314 | aF2.1414220333099365 315 | aF0.0061779022216796875 316 | aF0.029187917709350586 317 | aF-0.995607852935791 318 | aF2.1415061950683594 319 | aF-0.015707969665527344 320 | aF0.07155847549438477 321 | aa(lp30 322 | F0.004643917083740234 323 | aF-0.033705949783325195 324 | aF-0.9970581531524658 325 | aF2.1414220333099365 326 | aF0.0061779022216796875 327 | aF0.029187917709350586 328 | aF-0.995607852935791 329 | aF2.1415061950683594 330 | aF-0.012217044830322266 331 | aF0.06981277465820312 332 | aa. -------------------------------------------------------------------------------- /joint_control/robot_pose_data_json/StandInit: -------------------------------------------------------------------------------- 1 | [[4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5397986173629761, 0.9572582244873047, 0.007095034699887037, -0.01821630820631981], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5397986173629761, 0.9587922096252441, 0.007670100312680006, -0.018407996743917465], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5382646322250366, 0.9572582244873047, 0.0046021300368011, -0.01572340354323387], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5382646322250366, 0.9572582244873047, 0.00575273809954524, -0.018791373819112778], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5382646322250366, 0.9572582244873047, 0.005368884187191725, -0.021284278482198715], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5397986173629761, 0.9572582244873047, 0.006327803712338209, -0.018024619668722153], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5397986173629761, 0.9572582244873047, 0.008629020303487778, -0.01936691626906395], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5397986173629761, 0.9572582244873047, 0.006711180787533522, -0.018407996743917465], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5382646322250366, 0.9572582244873047, 0.00575273809954524, -0.018407996743917465], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5397986173629761, 0.9572582244873047, 0.006711180787533522, -0.01744907721877098], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5382646322250366, 0.9572582244873047, 0.0072867232374846935, -0.017257388681173325], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5382646322250366, 0.9572582244873047, 0.004793818574398756, -0.01936691626906395], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5382646322250366, 0.9572582244873047, 0.00747841177508235, -0.022434409707784653], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5397986173629761, 0.9572582244873047, 0.002876456594094634, -0.01936691626906395], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5397986173629761, 0.9572582244873047, 0.00575273809954524, -0.0164906345307827], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5397986173629761, 0.9572582244873047, 0.00575273809954524, -0.01936691626906395], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5397986173629761, 0.9572582244873047, 0.00575273809954524, -0.0164906345307827], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5397986173629761, 0.9572582244873047, 0.00575273809954524, -0.015531715005636215], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9019501209259033, 4.1961669921875e-05, -0.007627964019775391, -0.5382646322250366, 0.9572582244873047, 0.01016300544142723, -0.019750293344259262], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5397986173629761, 0.9572582244873047, 0.008629020303487778, -0.02032535895705223], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5382646322250366, 0.9572582244873047, 0.004218752961605787, -0.016682323068380356], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5382646322250366, 0.9572582244873047, 0.008629020303487778, -0.018407996743917465], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5397986173629761, 0.9572582244873047, 0.008629020303487778, -0.0164906345307827], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5382646322250366, 0.9572582244873047, 0.00575273809954524, -0.018407996743917465], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5382646322250366, 0.9572582244873047, 0.004793818574398756, -0.01994198188185692], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5397986173629761, 0.9572582244873047, 0.007670100312680006, -0.01744907721877098], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5382646322250366, 0.9572582244873047, 0.004793818574398756, -0.020708736032247543], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5397986173629761, 0.9572582244873047, 0.004027064424008131, -0.019750293344259262], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5397986173629761, 0.9572582244873047, 0.00575273809954524, -0.01744907721877098], [4.1961669921875e-05, -0.007627964019775391, -0.2530679702758789, 0.9004161357879639, 4.1961669921875e-05, -0.007627964019775391, -0.5382646322250366, 0.9572582244873047, 0.006136115174740553, -0.017257388681173325], [-0.022968053817749023, -0.024502038955688477, -0.23772811889648438, 0.8958139419555664, -0.022968053817749023, -0.02143406867980957, -0.5152546167373657, 0.941917896270752, -0.0339391864836216, 0.07631523162126541], [-0.19324207305908203, 0.1304318904876709, -0.4693620204925537, 0.9050180912017822, -0.19324207305908203, 0.06753802299499512, -0.16703666746616364, 0.9127721786499023, -0.003834549570456147, 0.018215958029031754], [-0.19324207305908203, 0.1304318904876709, -0.47089600563049316, 0.9065520763397217, -0.19324207305908203, 0.06753802299499512, -0.16703666746616364, 0.9127721786499023, -0.00402671517804265, 0.018599335104227066], [-0.19324207305908203, 0.1304318904876709, -0.4693620204925537, 0.9065520763397217, -0.19324207305908203, 0.06753802299499512, -0.16703666746616364, 0.9127721786499023, -0.004793469328433275, 0.019366566091775894], [-0.19324207305908203, 0.1304318904876709, -0.47089600563049316, 0.9065520763397217, -0.19324207305908203, 0.06753802299499512, -0.1685706526041031, 0.9112381935119629, -0.0049851578660309315, 0.019366566091775894], [-0.19324207305908203, 0.12889790534973145, -0.4693620204925537, 0.9065520763397217, -0.19324207305908203, 0.06907200813293457, -0.1685706526041031, 0.9127721786499023, -0.002876106882467866, 0.017448727041482925], [-0.19324207305908203, 0.1304318904876709, -0.4693620204925537, 0.9065520763397217, -0.19324207305908203, 0.06753802299499512, -0.16703666746616364, 0.9112381935119629, -0.003834549570456147, 0.020325008779764175], [-0.19324207305908203, 0.1304318904876709, -0.4693620204925537, 0.9065520763397217, -0.19324207305908203, 0.06753802299499512, -0.16703666746616364, 0.9112381935119629, -0.003834549570456147, 0.02224237099289894], [-0.19324207305908203, 0.12889790534973145, -0.4693620204925537, 0.9065520763397217, -0.19324207305908203, 0.06753802299499512, -0.16703666746616364, 0.9127721786499023, -0.006710831541568041, 0.017448727041482925], [-0.19324207305908203, 0.12889790534973145, -0.47089600563049316, 0.9065520763397217, -0.19324207305908203, 0.06753802299499512, -0.16703666746616364, 0.9112381935119629, -0.0019171873573213816, 0.017448727041482925], [-0.19324207305908203, 0.12889790534973145, -0.4693620204925537, 0.9065520763397217, -0.19324207305908203, 0.06753802299499512, -0.16703666746616364, 0.9112381935119629, -0.0019171873573213816, 0.022434059530496597], [-0.19324207305908203, 0.1304318904876709, -0.4693620204925537, 0.9065520763397217, -0.19324207305908203, 0.06753802299499512, -0.16703666746616364, 0.9127721786499023, -0.0011504332069307566, 0.016490284353494644], [-0.19477605819702148, 0.12889790534973145, -0.4693620204925537, 0.9065520763397217, -0.19477605819702148, 0.06753802299499512, -0.16703666746616364, 0.9127721786499023, -0.0009587446693331003, 0.020325008779764175], [-0.19324207305908203, 0.12889790534973145, -0.4693620204925537, 0.9065520763397217, -0.19324207305908203, 0.06753802299499512, -0.16703666746616364, 0.9112381935119629, -0.003067795420065522, 0.0166819728910923], [-0.19477605819702148, 0.1304318904876709, -0.4693620204925537, 0.9065520763397217, -0.19477605819702148, 0.06753802299499512, -0.16703666746616364, 0.9112381935119629, -0.003642861032858491, 0.019174400717020035], [-0.19477605819702148, 0.12889790534973145, -0.47089600563049316, 0.9065520763397217, -0.19477605819702148, 0.06907200813293457, -0.1685706526041031, 0.9112381935119629, -0.00575238885357976, 0.022434059530496597], [-0.19477605819702148, 0.1304318904876709, -0.4693620204925537, 0.9065520763397217, -0.19477605819702148, 0.06753802299499512, -0.16703666746616364, 0.9127721786499023, -0.00575238885357976, 0.02013332024216652], [-0.19324207305908203, 0.1304318904876709, -0.47089600563049316, 0.9065520763397217, -0.19324207305908203, 0.06753802299499512, -0.16703666746616364, 0.9127721786499023, -0.0019171873573213816, 0.019366566091775894], [-0.19477605819702148, 0.1304318904876709, -0.47089600563049316, 0.9065520763397217, -0.19477605819702148, 0.06753802299499512, -0.16703666746616364, 0.9127721786499023, -0.002876106882467866, 0.01840764656662941], [-0.027570009231567383, 0.004643917083740234, -0.5736739635467529, 0.9847860336303711, -0.027570009231567383, -0.004559993743896484, -0.2774845361709595, 0.9173741340637207, -0.011696640402078629, 0.044868770986795425], [-0.029103994369506836, 0.004643917083740234, -0.5736739635467529, 0.9847860336303711, -0.027570009231567383, -0.004559993743896484, -0.2774845361709595, 0.9173741340637207, -0.013614002615213394, 0.040841881185770035], [-0.2469320297241211, 0.12582993507385254, -0.2868161201477051, 0.9955241680145264, -0.2469320297241211, -0.12421202659606934, -0.30049455165863037, 1.0109481811523438, 0.015148337930440903, 0.11869174987077713]] -------------------------------------------------------------------------------- /software_installation/spark_agent.py: -------------------------------------------------------------------------------- 1 | '''Base agent for SimSpark, it implements the sense-think-act loop 2 | ''' 3 | from builtins import bytes 4 | import socket 5 | import struct 6 | from threading import Thread 7 | from math import pi, atan2, asin, cos, sin 8 | from sexpr import str2sexpr 9 | 10 | DEG_TO_RAD = pi / 180 11 | 12 | HINGE_JOINT_PERCEPTOR = "HJ" 13 | UNIVERSAL_JOINT_PERCEPTOR = "UJ" 14 | TOUCH_PERCEPTOR = "TCH" 15 | FORCE_RESISTANCE_PERCEPTOR = "FRP" 16 | ACCELEROMETER_PERCEPTOR = "ACC" 17 | GYRO_RATE_PERCEPTOR = "GYR" 18 | GAME_STATE_PERCEPTOR = "GS" 19 | GPS_PERCEPTOR = "GPS" 20 | BAT_PERCEPTOR = "BAT" 21 | SONAR_PERCEPTOR = "US" 22 | 23 | VISION_PERCEPTOR = "See" 24 | VISION_PERCEPTOR_TRUE_BALL = "ballpos" 25 | VISION_PERCEPTOR_TRUE_POS = "mypos" 26 | VISION_PERCEPTOR_BALL = "B" 27 | VISION_PERCEPTOR_LINE = "L" 28 | VISION_PERCEPTOR_TOP_RIGHT_FIELD_CORNER = "F1R" 29 | VISION_PERCEPTOR_BOTTOM_RIGHT_FIELD_CORNER = "F2R" 30 | VISION_PERCEPTOR_TOP_LEFT_FIELD_CORNER = "F1L" 31 | VISION_PERCEPTOR_BOTTOM_LEFT_FIELD_CORNER = "F2L" 32 | VISION_PERCEPTOR_TOP_RIGHT_GOAL_POST = "G1R" 33 | VISION_PERCEPTOR_BOTTOM_RIGHT_GOAL_POST = "G2R" 34 | VISION_PERCEPTOR_TOP_LEFT_GOAL_POST = "G1L" 35 | VISION_PERCEPTOR_BOTTOM_LEFT_GOAL_POST = "G2L" 36 | VISION_PERCEPTOR_AGENT = "P" 37 | VISION_PERCEPTOR_HEAD = "head" 38 | VISION_PERCEPTOR_RIGHT_LOWER_ARM = "rlowerarm" 39 | VISION_PERCEPTOR_LEFT_LOWER_ARM = "llowerarm" 40 | VISION_PERCEPTOR_RIGHT_FOOT = "rfoot" 41 | VISION_PERCEPTOR_LEFT_FOOT = "lfoot" 42 | BOTTOM_CAMERA = 'BottomCamera' 43 | TOP_CAMERA = 'TopCamera' 44 | 45 | 46 | JOINT_SENSOR_NAMES = {"hj1": 'HeadYaw', 47 | "hj2": 'HeadPitch', 48 | "laj1": 'LShoulderPitch', 49 | "laj2": 'LShoulderRoll', 50 | "laj3": 'LElbowYaw', 51 | "laj4": 'LElbowRoll', 52 | "llj1": 'LHipYawPitch', 53 | "llj2": 'LHipRoll', 54 | "llj3": 'LHipPitch', 55 | "llj4": 'LKneePitch', 56 | "llj5": 'LAnklePitch', 57 | "llj6": 'LAnkleRoll', 58 | "raj1": 'RShoulderPitch', 59 | "raj2": 'RShoulderRoll', 60 | "raj3": 'RElbowYaw', 61 | "raj4": 'RElbowRoll', 62 | "rlj1": 'RHipYawPitch', 63 | "rlj2": 'RHipRoll', 64 | "rlj3": 'RHipPitch', 65 | "rlj4": 'RKneePitch', 66 | "rlj5": 'RAnklePitch', 67 | "rlj6": 'RAnkleRoll'} 68 | 69 | JOINT_CMD_NAMES = {'HeadYaw': "he1", 70 | 'HeadPitch': "he2", 71 | 'LShoulderPitch': "lae1", 72 | 'LShoulderRoll': "lae2", 73 | 'LElbowYaw': "lae3", 74 | 'LElbowRoll': "lae4", 75 | 'LHipYawPitch': "lle1", 76 | 'LHipRoll': "lle2", 77 | 'LHipPitch': "lle3", 78 | 'LKneePitch': "lle4", 79 | 'LAnklePitch': "lle5", 80 | 'LAnkleRoll': "lle6", 81 | 'RShoulderPitch': "rae1", 82 | 'RShoulderRoll': "rae2", 83 | 'RElbowYaw': "rae3", 84 | 'RElbowRoll': "rae4", 85 | 'RHipYawPitch': "rle1", 86 | 'RHipRoll': "rle2", 87 | 'RHipPitch': "rle3", 88 | 'RKneePitch': "rle4", 89 | 'RAnklePitch': "rle5", 90 | 'RAnkleRoll': "rle6"} 91 | 92 | 93 | # some joints are inverted in simspark compared with real NAO 94 | INVERSED_JOINTS = ['HeadPitch', 95 | 'LShoulderPitch', 96 | 'RShoulderPitch', 97 | 'LHipPitch', 98 | 'RHipPitch', 99 | 'LKneePitch', 100 | 'RKneePitch', 101 | 'LAnklePitch', 102 | 'RAnklePitch'] 103 | 104 | 105 | class GameState: 106 | def __init__(self): 107 | self.time = 0 108 | self.play_mode = 'unknown' 109 | self.unum = 0 110 | self.team = 'unknown' 111 | 112 | def update(self, sexp): 113 | for s in sexp: 114 | name = s[0] 115 | if name == 't': 116 | self.time = float(s[1]) 117 | elif name == 'pm': 118 | self.play_mode = s[1] 119 | elif name == 'unum': 120 | self.unum = int(s[1]) 121 | elif name == 'team': 122 | self.team = s[1] 123 | 124 | 125 | class Perception: 126 | def __init__(self): 127 | self.time = 0 128 | self.joint = {} 129 | self.joint_temperature = {} 130 | self.fsr = {} 131 | self.see = [{}, {}] 132 | self.game_state = GameState() 133 | self.gps = {} 134 | self.imu = [0, 0] # [AngleX, AngleY] 135 | self.us = {} 136 | 137 | def update(self, sexp): 138 | for s in sexp: 139 | name = s[0] 140 | if name == 'time': 141 | self.time = float(s[1][1]) 142 | elif name == GAME_STATE_PERCEPTOR: 143 | self.game_state.update(s[1:]) 144 | elif name == GYRO_RATE_PERCEPTOR: 145 | self.gyr = [float(v) for v in s[2][1:]] 146 | elif name == ACCELEROMETER_PERCEPTOR: 147 | self.acc = [float(v) for v in s[2][1:]] 148 | elif name == HINGE_JOINT_PERCEPTOR: 149 | jointv = {} 150 | for i in s[1:]: 151 | jointv[i[0]] = i[1] 152 | name = JOINT_SENSOR_NAMES[jointv['n']] 153 | if 'ax' in jointv: 154 | self.joint[name] = float(jointv['ax']) * DEG_TO_RAD * (-1 if name in INVERSED_JOINTS else 1) 155 | if 'tp' in jointv: 156 | self.joint_temperature[name] = float(jointv['tp']) 157 | elif name == VISION_PERCEPTOR or name == TOP_CAMERA: 158 | self.see[0] = self._parse_vision(s[1:]) 159 | elif name == BOTTOM_CAMERA: 160 | self.see[1] = self._parse_vision(s[1:]) 161 | elif name == FORCE_RESISTANCE_PERCEPTOR: 162 | self.fsr[s[1][1]] = {s[2][0]: [float(v) for v in s[2][1:]], 163 | s[3][0]: [float(v) for v in s[3][1:]]} 164 | elif name == GPS_PERCEPTOR: 165 | self.gps[s[1][1]] = [float(v) for v in s[2][1:]] 166 | elif name == BAT_PERCEPTOR: 167 | self.bat = float(s[1]) 168 | elif name == SONAR_PERCEPTOR: 169 | self.us[s[1]] = [float(dist) for dist in s[2]] 170 | else: 171 | raise RuntimeError('unknown perception: ' + str(s)) 172 | 173 | if 'torso' in self.gps: 174 | data = self.gps['torso'] 175 | angX = atan2(data[9], data[10]) 176 | angY = asin(-data[8]) 177 | # convert angle range: angY in [-pi, pi], angX in [-pi/2, pi/2] 178 | if (abs(angX) > pi / 2): 179 | angX = pi + angX 180 | angX = atan2(sin(angX), cos(angX)) # normalize 181 | angY = pi - angY 182 | angY = atan2(sin(angY), cos(angY)) # normalize 183 | self.imu = [angX, angY] 184 | 185 | def _parse_vision(self, sexp): 186 | see = {} 187 | see[VISION_PERCEPTOR_LINE] = [] 188 | see[VISION_PERCEPTOR_AGENT] = [] 189 | 190 | for i in sexp: 191 | if i[0] == VISION_PERCEPTOR_LINE or i[0] == VISION_PERCEPTOR_AGENT: 192 | see[i[0]].append(i[1:]) 193 | else: 194 | see[i[0]] = i[1:] 195 | return see 196 | 197 | 198 | class Action(object): 199 | def __init__(self): 200 | self.stiffness = {} 201 | self.speed = {} 202 | 203 | def to_commands(self): 204 | speed = ['(%s %.2f)' % (JOINT_CMD_NAMES[k], self.speed[k] * (-1 if k in INVERSED_JOINTS else 1)) for k in self.speed] 205 | stiffness = ['(%ss %.2f)' % (JOINT_CMD_NAMES[k], self.stiffness[k]) for k in self.stiffness] 206 | return ''.join(speed + stiffness) 207 | 208 | 209 | class SparkAgent(object): 210 | def __init__(self, simspark_ip='localhost', 211 | simspark_port=3100, 212 | teamname='DAInamite', 213 | player_id=0, 214 | sync_mode=True): 215 | # connect to simspark, get palyer_id 216 | self.sync_mode = sync_mode 217 | self.connect(simspark_ip, simspark_port) 218 | self.perception = Perception() 219 | 220 | self.send_command('(scene rsg/agent/naov4/nao.rsg)') 221 | self.sense() # only need to get msg from simspark 222 | init_cmd = ('(init (unum ' + str(player_id) + ')(teamname ' + teamname + '))') 223 | self.send_command(init_cmd) 224 | self.thread = None 225 | 226 | while player_id == 0: 227 | self.sense() 228 | self.send_command('') 229 | player_id = self.perception.game_state.unum 230 | self.player_id = player_id 231 | 232 | def act(self, action): 233 | commands = action.to_commands() 234 | self.send_command(commands) 235 | 236 | def send_command(self, commands): 237 | if self.sync_mode: 238 | commands += '(syn)' 239 | self.socket.sendall(struct.pack(b"!I", len(commands)) + bytes(commands, encoding='utf8')) 240 | 241 | def connect(self, simspark_ip, simspark_port): 242 | self.socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM) 243 | self.socket.connect((simspark_ip, simspark_port)) 244 | 245 | def sense(self): 246 | length = b'' 247 | while(len(length) < 4): 248 | length += self.socket.recv(4 - len(length)) 249 | length = struct.unpack("!I", length)[0] 250 | msg = b'' 251 | while len(msg) < length: 252 | msg += self.socket.recv(length - len(msg)) 253 | 254 | sexp = str2sexpr(msg.decode()) 255 | self.perception.update(sexp) 256 | return self.perception 257 | 258 | def think(self, perception): 259 | action = Action() 260 | return action 261 | 262 | def sense_think_act(self): 263 | perception = self.sense() 264 | action = self.think(perception) 265 | self.act(action) 266 | 267 | def run(self): 268 | while True: 269 | self.sense_think_act() 270 | 271 | def start(self): 272 | if self.thread is None: 273 | self.thread = Thread(target=self.run) 274 | self.thread.daemon = True 275 | self.thread.start() 276 | 277 | 278 | if '__main__' == __name__: 279 | agent = SparkAgent() 280 | agent.run() 281 | -------------------------------------------------------------------------------- /nao_doc/vision.rst: -------------------------------------------------------------------------------- 1 | RobocupVision 2 | ############# 3 | 4 | :version: 2.1.2 5 | 6 | Interactive proxy to ALModule 7 | 8 | isStatsEnabled() 9 | ================ 10 | 11 | 12 | 13 | 14 | enableStats() 15 | ============= 16 | 17 | 18 | 19 | 20 | stats() 21 | ======= 22 | 23 | 24 | 25 | 26 | clearStats() 27 | ============ 28 | 29 | 30 | 31 | 32 | isTraceEnabled() 33 | ================ 34 | 35 | 36 | 37 | 38 | enableTrace() 39 | ============= 40 | 41 | 42 | 43 | 44 | exit() 45 | ====== 46 | Exits and unregisters the module. 47 | 48 | 49 | 50 | pCall() 51 | ======= 52 | NAOqi1 pCall method. 53 | 54 | 55 | 56 | version() 57 | ========= 58 | Returns the version of the module. 59 | 60 | 61 | Returns 62 | ------- 63 | A string containing the version of the module. 64 | 65 | ping() 66 | ====== 67 | Just a ping. Always returns true 68 | 69 | 70 | Returns 71 | ------- 72 | returns true 73 | 74 | getMethodList() 75 | =============== 76 | Retrieves the module's method list. 77 | 78 | 79 | Returns 80 | ------- 81 | An array of method names. 82 | 83 | getMethodHelp(methodName) 84 | ========================= 85 | Retrieves a method's description. 86 | 87 | Parameters 88 | ---------- 89 | :methodName: The name of the method. 90 | 91 | Returns 92 | ------- 93 | A structure containing the method's description. 94 | 95 | getModuleHelp() 96 | =============== 97 | Retrieves the module's description. 98 | 99 | 100 | Returns 101 | ------- 102 | A structure describing the module. 103 | 104 | wait(id, timeoutPeriod) 105 | ======================= 106 | Wait for the end of a long running method that was called using 'post' 107 | 108 | Parameters 109 | ---------- 110 | :id: The ID of the method that was returned when calling the method using 'post' 111 | :timeoutPeriod: The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. 112 | 113 | Returns 114 | ------- 115 | True if the timeout period terminated. False if the method returned. 116 | 117 | isRunning(id) 118 | ============= 119 | Returns true if the method is currently running. 120 | 121 | Parameters 122 | ---------- 123 | :id: The ID of the method that was returned when calling the method using 'post' 124 | 125 | Returns 126 | ------- 127 | True if the method is currently running 128 | 129 | stop(id) 130 | ======== 131 | returns true if the method is currently running 132 | 133 | Parameters 134 | ---------- 135 | :id: the ID of the method to wait for 136 | 137 | 138 | getBrokerName() 139 | =============== 140 | Gets the name of the parent broker. 141 | 142 | 143 | Returns 144 | ------- 145 | The name of the parent broker. 146 | 147 | getUsage(name) 148 | ============== 149 | Gets the method usage string. This summarises how to use the method. 150 | 151 | Parameters 152 | ---------- 153 | :name: The name of the method. 154 | 155 | Returns 156 | ------- 157 | A string that summarises the usage of the method. 158 | 159 | getDescription() 160 | ================ 161 | gets module description message 162 | 163 | 164 | Returns 165 | ------- 166 | description 167 | 168 | getVisionResults(cameraId) 169 | ========================== 170 | Returns the vision results for the given camera. 171 | 172 | Parameters 173 | ---------- 174 | :cameraId: 0 for top camera and 1 for bottom camera 175 | 176 | Returns 177 | ------- 178 | vision result as list of integer list 179 | 180 | getYUV422Image(cameraId) 181 | ======================== 182 | Returns an image in yuv422 format. 183 | 184 | Parameters 185 | ---------- 186 | :cameraId: 0 for top camera and 1 for bottom camera 187 | 188 | Returns 189 | ------- 190 | image as byte array 191 | 192 | getYUV422ImageWithTime(cameraId) 193 | ================================ 194 | Returns an image in yuv422 format with time. 195 | 196 | Parameters 197 | ---------- 198 | :cameraId: 0 for top camera and 1 for bottom camera 199 | 200 | Returns 201 | ------- 202 | [[tv_sec, tv_usec], image as byte array] 203 | 204 | getYUV422ImageWithTimeCameraMatrixAndBodyContour(cameraId) 205 | ========================================================== 206 | Returns an image in yuv422 format with time, camera matrix and body contour. 207 | 208 | Parameters 209 | ---------- 210 | :cameraId: 0 for top camera and 1 for bottom camera 211 | 212 | Returns 213 | ------- 214 | [[tv_sec, tv_usec], image as byte array, camera matrix, body contour] 215 | 216 | getBGR24Image(cameraId) 217 | ======================= 218 | Returns an image in bgr24 format. 219 | 220 | Parameters 221 | ---------- 222 | :cameraId: 0 for top camera and 1 for bottom camera 223 | 224 | Returns 225 | ------- 226 | image as byte array 227 | 228 | getBGR24ImageWithTime(cameraId) 229 | =============================== 230 | Returns an image in bgr24 format with time. 231 | 232 | Parameters 233 | ---------- 234 | :cameraId: 0 for top camera and 1 for bottom camera 235 | 236 | Returns 237 | ------- 238 | [[tv_sec, tv_usec], image as byte array] 239 | 240 | getReducedYUV422Image(cameraId) 241 | =============================== 242 | Returns an reduced image in yuv422 format. 243 | 244 | Parameters 245 | ---------- 246 | :cameraId: 0 for top camera and 1 for bottom camera 247 | 248 | Returns 249 | ------- 250 | image as byte array 251 | 252 | getReducedBGR24Image(cameraId) 253 | ============================== 254 | Returns an reduced image in bgr24 format. 255 | 256 | Parameters 257 | ---------- 258 | :cameraId: 0 for top camera and 1 for bottom camera 259 | 260 | Returns 261 | ------- 262 | image as byte array 263 | 264 | getReducedBGR24ImageWithTime(cameraId) 265 | ====================================== 266 | Returns an reduced image in bgr24 format with time. 267 | 268 | Parameters 269 | ---------- 270 | :cameraId: 0 for top camera and 1 for bottom camera 271 | 272 | Returns 273 | ------- 274 | [[tv_sec, tv_usec], image as byte array] 275 | 276 | getAugmentedRealityMarkers(cameraId) 277 | ==================================== 278 | Returns ArUco augmented reality markers with time. 279 | 280 | Parameters 281 | ---------- 282 | :cameraId: 0 for top camera and 1 for bottom camera 283 | 284 | Returns 285 | ------- 286 | [[tv_sec, tv_usec], markers] 287 | 288 | setCameraConfiguration(cameraId, key, value) 289 | ============================================ 290 | Sets camera configuration. 291 | 292 | Parameters 293 | ---------- 294 | :cameraId: 0 for top camera and 1 for bottom camera 295 | :key: camera configuration key 296 | :value: camera configuration value 297 | 298 | 299 | getCameraConfiguration(cameraId, key) 300 | ===================================== 301 | Gets camera configuration. 302 | 303 | Parameters 304 | ---------- 305 | :cameraId: 0 for top camera and 1 for bottom camera 306 | :key: camera configuration key 307 | 308 | Returns 309 | ------- 310 | camera configuration value 311 | 312 | setVisionConfiguration(cameraId, key, value) 313 | ============================================ 314 | Sets vision configuration. 315 | 316 | Parameters 317 | ---------- 318 | :cameraId: 0 for top camera and 1 for bottom camera 319 | :key: vision configuration key 320 | :value: vision configuration value 321 | 322 | 323 | setConfig(list of key value pairs) 324 | ================================== 325 | Sets configuration. 326 | 327 | Parameters 328 | ---------- 329 | :list of key value pairs: [[key0, value0], [key1, value1], ...] 330 | 331 | 332 | getVisionConfiguration(cameraId, key) 333 | ===================================== 334 | Gets vision configuration. 335 | 336 | Parameters 337 | ---------- 338 | :cameraId: 0 for top camera and 1 for bottom camera 339 | :key: vision configuration key 340 | 341 | Returns 342 | ------- 343 | vision configuration value 344 | 345 | getConfig(key) 346 | ============== 347 | Gets configuration. 348 | 349 | Parameters 350 | ---------- 351 | :key: camera_name.group.key_name 352 | 353 | Returns 354 | ------- 355 | configuration value 356 | 357 | getAllConfig() 358 | ============== 359 | Gets all vision configuration. 360 | 361 | 362 | Returns 363 | ------- 364 | configuration value 365 | 366 | setCameraInfo(cameraId, key, value) 367 | =================================== 368 | Sets camera info (intrinsic matrix and distortion coefficients). 369 | 370 | Parameters 371 | ---------- 372 | :cameraId: 0 for top camera and 1 for bottom camera 373 | :key: configuration key 374 | :value: configuration value 375 | 376 | 377 | getCameraInfo(cameraId, key) 378 | ============================ 379 | Gets camera info (intrinsic matrix and distortion coefficients). 380 | 381 | Parameters 382 | ---------- 383 | :cameraId: 0 for top camera and 1 for bottom camera 384 | :key: configuration key 385 | 386 | Returns 387 | ------- 388 | configuration value 389 | 390 | setAugmentedRealityConfiguration(cameraId, key, value) 391 | ====================================================== 392 | Sets augmented reality configuration. 393 | 394 | Parameters 395 | ---------- 396 | :cameraId: 0 for top camera and 1 for bottom camera 397 | :key: augmented reality configuration key 398 | :value: augmented reality configuration value 399 | 400 | 401 | getAugmentedRealityConfiguration(cameraId, key) 402 | =============================================== 403 | Gets augmented reality configuration. 404 | 405 | Parameters 406 | ---------- 407 | :cameraId: 0 for top camera and 1 for bottom camera 408 | :key: augmented reality configuration key 409 | 410 | Returns 411 | ------- 412 | augmented reality configuration value 413 | 414 | enableVisionProcessing(cameraId, enable) 415 | ======================================== 416 | enable/disable vision processing. 417 | 418 | Parameters 419 | ---------- 420 | :cameraId: 0 for top camera and 1 for bottom camera 421 | :enable: enable 422 | 423 | 424 | isVisionProcessingEnabled(cameraId) 425 | =================================== 426 | Is vision processing enabled? 427 | 428 | Parameters 429 | ---------- 430 | :cameraId: 0 for top camera and 1 for bottom camera 431 | 432 | 433 | enableCameraMatrixUsage(cameraId, enable) 434 | ========================================= 435 | enable/disable the camera matrix usage in the vision processing. 436 | 437 | Parameters 438 | ---------- 439 | :cameraId: 0 for top camera and 1 for bottom camera 440 | :enable: enable 441 | 442 | 443 | isCameraMatrixUsageEnabled(cameraId) 444 | ==================================== 445 | Is the camera is used in the vision processing?? 446 | 447 | Parameters 448 | ---------- 449 | :cameraId: 0 for top camera and 1 for bottom camera 450 | 451 | 452 | setVideoRecording(cameraId, enable) 453 | =================================== 454 | enable/disable video recording. 455 | 456 | Parameters 457 | ---------- 458 | :cameraId: 0 for top camera and 1 for bottom camera 459 | :enable: enable 460 | 461 | 462 | isVideoRecording(cameraId) 463 | ========================== 464 | Is video recording enabled? 465 | 466 | Parameters 467 | ---------- 468 | :cameraId: 0 for top camera and 1 for bottom camera 469 | 470 | 471 | writeCurrentConfigurationsIntoPrefFile() 472 | ======================================== 473 | Writes the current vision and camera settings into the preference file. 474 | 475 | 476 | 477 | saveConfig() 478 | ============ 479 | Writes the current vision and camera settings into the preference file. 480 | 481 | 482 | 483 | snapshot() 484 | ========== 485 | snapshot one frame of image 486 | 487 | 488 | 489 | getBodyContours(cameraId) 490 | ========================= 491 | Returns the body contours. 492 | 493 | Parameters 494 | ---------- 495 | :cameraId: 0 for top camera and 1 for bottom camera 496 | 497 | Returns 498 | ------- 499 | body contours as list of integer list 500 | -------------------------------------------------------------------------------- /software_installation/numpy_baisc.ipynb: -------------------------------------------------------------------------------- 1 | { 2 | "metadata": { 3 | "name": "" 4 | }, 5 | "nbformat": 3, 6 | "nbformat_minor": 0, 7 | "worksheets": [ 8 | { 9 | "cells": [ 10 | { 11 | "cell_type": "heading", 12 | "level": 1, 13 | "metadata": { 14 | "slideshow": { 15 | "slide_type": "slide" 16 | } 17 | }, 18 | "source": [ 19 | "Numpy Basic" 20 | ] 21 | }, 22 | { 23 | "cell_type": "markdown", 24 | "metadata": {}, 25 | "source": [ 26 | "[Numpy](http://numpy.org/) contains core routines for doing fast vector, matrix, and linear algebra-type operations in Python." 27 | ] 28 | }, 29 | { 30 | "cell_type": "code", 31 | "collapsed": false, 32 | "input": [ 33 | "from numpy import *" 34 | ], 35 | "language": "python", 36 | "metadata": {}, 37 | "outputs": [], 38 | "prompt_number": 1 39 | }, 40 | { 41 | "cell_type": "heading", 42 | "level": 2, 43 | "metadata": {}, 44 | "source": [ 45 | "Create array" 46 | ] 47 | }, 48 | { 49 | "cell_type": "code", 50 | "collapsed": false, 51 | "input": [ 52 | "array([1, 2, 3])" 53 | ], 54 | "language": "python", 55 | "metadata": {}, 56 | "outputs": [ 57 | { 58 | "metadata": {}, 59 | "output_type": "pyout", 60 | "prompt_number": 2, 61 | "text": [ 62 | "array([1, 2, 3])" 63 | ] 64 | } 65 | ], 66 | "prompt_number": 2 67 | }, 68 | { 69 | "cell_type": "code", 70 | "collapsed": false, 71 | "input": [ 72 | "array([[0,1],[1,0]], 'f')" 73 | ], 74 | "language": "python", 75 | "metadata": {}, 76 | "outputs": [ 77 | { 78 | "metadata": {}, 79 | "output_type": "pyout", 80 | "prompt_number": 4, 81 | "text": [ 82 | "array([[ 0., 1.],\n", 83 | " [ 1., 0.]], dtype=float32)" 84 | ] 85 | } 86 | ], 87 | "prompt_number": 4 88 | }, 89 | { 90 | "cell_type": "code", 91 | "collapsed": false, 92 | "input": [ 93 | "zeros((2, 3))" 94 | ], 95 | "language": "python", 96 | "metadata": {}, 97 | "outputs": [ 98 | { 99 | "metadata": {}, 100 | "output_type": "pyout", 101 | "prompt_number": 7, 102 | "text": [ 103 | "array([[ 0., 0., 0.],\n", 104 | " [ 0., 0., 0.]])" 105 | ] 106 | } 107 | ], 108 | "prompt_number": 7 109 | }, 110 | { 111 | "cell_type": "code", 112 | "collapsed": false, 113 | "input": [ 114 | "identity(4)" 115 | ], 116 | "language": "python", 117 | "metadata": {}, 118 | "outputs": [ 119 | { 120 | "metadata": {}, 121 | "output_type": "pyout", 122 | "prompt_number": 8, 123 | "text": [ 124 | "array([[ 1., 0., 0., 0.],\n", 125 | " [ 0., 1., 0., 0.],\n", 126 | " [ 0., 0., 1., 0.],\n", 127 | " [ 0., 0., 0., 1.]])" 128 | ] 129 | } 130 | ], 131 | "prompt_number": 8 132 | }, 133 | { 134 | "cell_type": "heading", 135 | "level": 2, 136 | "metadata": {}, 137 | "source": [ 138 | "Slicing" 139 | ] 140 | }, 141 | { 142 | "cell_type": "code", 143 | "collapsed": false, 144 | "input": [ 145 | "a = array([[0, 1, 2],[3, 4, 5]])\n", 146 | "a" 147 | ], 148 | "language": "python", 149 | "metadata": {}, 150 | "outputs": [ 151 | { 152 | "metadata": {}, 153 | "output_type": "pyout", 154 | "prompt_number": 3, 155 | "text": [ 156 | "array([[0, 1, 2],\n", 157 | " [3, 4, 5]])" 158 | ] 159 | } 160 | ], 161 | "prompt_number": 3 162 | }, 163 | { 164 | "cell_type": "code", 165 | "collapsed": false, 166 | "input": [ 167 | "a[0][0]" 168 | ], 169 | "language": "python", 170 | "metadata": {}, 171 | "outputs": [ 172 | { 173 | "metadata": {}, 174 | "output_type": "pyout", 175 | "prompt_number": 4, 176 | "text": [ 177 | "0" 178 | ] 179 | } 180 | ], 181 | "prompt_number": 4 182 | }, 183 | { 184 | "cell_type": "code", 185 | "collapsed": false, 186 | "input": [ 187 | "a[0, 0]" 188 | ], 189 | "language": "python", 190 | "metadata": {}, 191 | "outputs": [ 192 | { 193 | "metadata": {}, 194 | "output_type": "pyout", 195 | "prompt_number": 5, 196 | "text": [ 197 | "0" 198 | ] 199 | } 200 | ], 201 | "prompt_number": 5 202 | }, 203 | { 204 | "cell_type": "code", 205 | "collapsed": false, 206 | "input": [ 207 | "a[-1, 0]" 208 | ], 209 | "language": "python", 210 | "metadata": {}, 211 | "outputs": [ 212 | { 213 | "metadata": {}, 214 | "output_type": "pyout", 215 | "prompt_number": 6, 216 | "text": [ 217 | "3" 218 | ] 219 | } 220 | ], 221 | "prompt_number": 6 222 | }, 223 | { 224 | "cell_type": "code", 225 | "collapsed": false, 226 | "input": [ 227 | "a[:, 1]" 228 | ], 229 | "language": "python", 230 | "metadata": {}, 231 | "outputs": [ 232 | { 233 | "metadata": {}, 234 | "output_type": "pyout", 235 | "prompt_number": 9, 236 | "text": [ 237 | "array([1, 4])" 238 | ] 239 | } 240 | ], 241 | "prompt_number": 9 242 | }, 243 | { 244 | "cell_type": "code", 245 | "collapsed": false, 246 | "input": [ 247 | "a[0, :-1]" 248 | ], 249 | "language": "python", 250 | "metadata": {}, 251 | "outputs": [ 252 | { 253 | "metadata": {}, 254 | "output_type": "pyout", 255 | "prompt_number": 8, 256 | "text": [ 257 | "array([0, 1])" 258 | ] 259 | } 260 | ], 261 | "prompt_number": 8 262 | }, 263 | { 264 | "cell_type": "heading", 265 | "level": 2, 266 | "metadata": {}, 267 | "source": [ 268 | "Operation" 269 | ] 270 | }, 271 | { 272 | "cell_type": "code", 273 | "collapsed": false, 274 | "input": [ 275 | "0.5 * identity(2)" 276 | ], 277 | "language": "python", 278 | "metadata": {}, 279 | "outputs": [ 280 | { 281 | "metadata": {}, 282 | "output_type": "pyout", 283 | "prompt_number": 10, 284 | "text": [ 285 | "array([[ 0.5, 0. ],\n", 286 | " [ 0. , 0.5]])" 287 | ] 288 | } 289 | ], 290 | "prompt_number": 10 291 | }, 292 | { 293 | "cell_type": "code", 294 | "collapsed": false, 295 | "input": [ 296 | "identity(2) * 0.3 + array([[1, 0], [0, 0]])" 297 | ], 298 | "language": "python", 299 | "metadata": {}, 300 | "outputs": [ 301 | { 302 | "metadata": {}, 303 | "output_type": "pyout", 304 | "prompt_number": 11, 305 | "text": [ 306 | "array([[ 1.3, 0. ],\n", 307 | " [ 0. , 0.3]])" 308 | ] 309 | } 310 | ], 311 | "prompt_number": 11 312 | }, 313 | { 314 | "cell_type": "code", 315 | "collapsed": false, 316 | "input": [ 317 | "a0 = random.random((3,3))\n", 318 | "a1 = random.random((3,3))" 319 | ], 320 | "language": "python", 321 | "metadata": {}, 322 | "outputs": [], 323 | "prompt_number": 13 324 | }, 325 | { 326 | "cell_type": "code", 327 | "collapsed": false, 328 | "input": [ 329 | "a0" 330 | ], 331 | "language": "python", 332 | "metadata": {}, 333 | "outputs": [ 334 | { 335 | "metadata": {}, 336 | "output_type": "pyout", 337 | "prompt_number": 27, 338 | "text": [ 339 | "array([[ 0.84258984, 0.3678207 , 0.87769208],\n", 340 | " [ 0.36909916, 0.42353022, 0.54863083],\n", 341 | " [ 0.08999536, 0.84152716, 0.51809746]])" 342 | ] 343 | } 344 | ], 345 | "prompt_number": 27 346 | }, 347 | { 348 | "cell_type": "code", 349 | "collapsed": false, 350 | "input": [ 351 | "a1" 352 | ], 353 | "language": "python", 354 | "metadata": {}, 355 | "outputs": [ 356 | { 357 | "metadata": {}, 358 | "output_type": "pyout", 359 | "prompt_number": 28, 360 | "text": [ 361 | "array([[ 0.61921349, 0.97088541, 0.29053039],\n", 362 | " [ 0.55585198, 0.64892932, 0.76012311],\n", 363 | " [ 0.18926575, 0.147177 , 0.28912562]])" 364 | ] 365 | } 366 | ], 367 | "prompt_number": 28 368 | }, 369 | { 370 | "cell_type": "code", 371 | "collapsed": false, 372 | "input": [ 373 | "a0 * a1" 374 | ], 375 | "language": "python", 376 | "metadata": {}, 377 | "outputs": [ 378 | { 379 | "metadata": {}, 380 | "output_type": "pyout", 381 | "prompt_number": 29, 382 | "text": [ 383 | "array([[ 0.52174299, 0.35711175, 0.25499623],\n", 384 | " [ 0.2051645 , 0.27484118, 0.41702697],\n", 385 | " [ 0.01703304, 0.12385344, 0.14979525]])" 386 | ] 387 | } 388 | ], 389 | "prompt_number": 29 390 | }, 391 | { 392 | "cell_type": "code", 393 | "collapsed": false, 394 | "input": [ 395 | "a0.dot(a1)" 396 | ], 397 | "language": "python", 398 | "metadata": {}, 399 | "outputs": [ 400 | { 401 | "metadata": {}, 402 | "output_type": "pyout", 403 | "prompt_number": 30, 404 | "text": [ 405 | "array([[ 0.8923139 , 1.1859239 , 0.77815024],\n", 406 | " [ 0.56780831, 0.71394001, 0.58779286],\n", 407 | " [ 0.62154898, 0.70971886, 0.81560588]])" 408 | ] 409 | } 410 | ], 411 | "prompt_number": 30 412 | }, 413 | { 414 | "cell_type": "code", 415 | "collapsed": false, 416 | "input": [ 417 | "dot(a0, a1)" 418 | ], 419 | "language": "python", 420 | "metadata": {}, 421 | "outputs": [ 422 | { 423 | "metadata": {}, 424 | "output_type": "pyout", 425 | "prompt_number": 31, 426 | "text": [ 427 | "array([[ 0.8923139 , 1.1859239 , 0.77815024],\n", 428 | " [ 0.56780831, 0.71394001, 0.58779286],\n", 429 | " [ 0.62154898, 0.70971886, 0.81560588]])" 430 | ] 431 | } 432 | ], 433 | "prompt_number": 31 434 | }, 435 | { 436 | "cell_type": "code", 437 | "collapsed": false, 438 | "input": [ 439 | "a0.T" 440 | ], 441 | "language": "python", 442 | "metadata": {}, 443 | "outputs": [ 444 | { 445 | "metadata": {}, 446 | "output_type": "pyout", 447 | "prompt_number": 32, 448 | "text": [ 449 | "array([[ 0.84258984, 0.36909916, 0.08999536],\n", 450 | " [ 0.3678207 , 0.42353022, 0.84152716],\n", 451 | " [ 0.87769208, 0.54863083, 0.51809746]])" 452 | ] 453 | } 454 | ], 455 | "prompt_number": 32 456 | }, 457 | { 458 | "cell_type": "code", 459 | "collapsed": false, 460 | "input": [ 461 | "linalg.pinv(a0).dot(a0)" 462 | ], 463 | "language": "python", 464 | "metadata": {}, 465 | "outputs": [ 466 | { 467 | "metadata": {}, 468 | "output_type": "pyout", 469 | "prompt_number": 15, 470 | "text": [ 471 | "array([[ 1.00000000e+00, -8.88178420e-16, -8.88178420e-16],\n", 472 | " [ -8.88178420e-16, 1.00000000e+00, -1.77635684e-15],\n", 473 | " [ 2.22044605e-15, 2.66453526e-15, 1.00000000e+00]])" 474 | ] 475 | } 476 | ], 477 | "prompt_number": 15 478 | }, 479 | { 480 | "cell_type": "markdown", 481 | "metadata": {}, 482 | "source": [ 483 | "## Reference\n", 484 | "* [Lecture 2 Numpy in scientific python lectures](http://nbviewer.ipython.org/github/jrjohansson/scientific-python-lectures/blob/master/Lecture-2-Numpy.ipynb)" 485 | ] 486 | } 487 | ], 488 | "metadata": {} 489 | } 490 | ] 491 | } -------------------------------------------------------------------------------- /joint_control/learn_posture.ipynb: -------------------------------------------------------------------------------- 1 | { 2 | "cells": [ 3 | { 4 | "cell_type": "markdown", 5 | "metadata": {}, 6 | "source": [ 7 | "# Learn Posture" 8 | ] 9 | }, 10 | { 11 | "cell_type": "markdown", 12 | "metadata": {}, 13 | "source": [ 14 | "use machine learning to recognize robot's posture (following the example in [scikit-learn-intro.ipynb](./scikit-learn-intro.ipynb) )" 15 | ] 16 | }, 17 | { 18 | "cell_type": "markdown", 19 | "metadata": {}, 20 | "source": [ 21 | "## 1. Data collection\n", 22 | "\n", 23 | "We have colleceted data before, you need to add new data if you want to add new posture.\n", 24 | "\n", 25 | "* the dateset are in *robot_pose_data* folder\n", 26 | "* each file contains the data belongs to this posture, e.g. the data in *Back* file are collected when robot was in \"Back\" posture\n", 27 | "* the data file can be load by ```pickle```, e.g. ```pickle.load(open('Back', 'rb'))```, the data is a list of feature data\n", 28 | "* the features (e.g. each row of the data) are ['LHipYawPitch', 'LHipRoll', 'LHipPitch', 'LKneePitch', 'RHipYawPitch', 'RHipRoll', 'RHipPitch', 'RKneePitch', 'AngleX', 'AngleY'], where 'AngleX' and 'AngleY' are body angle (e.g. ```Perception.imu```) and others are joint angles." 29 | ] 30 | }, 31 | { 32 | "cell_type": "markdown", 33 | "metadata": {}, 34 | "source": [ 35 | "## 2. Data preprocessing" 36 | ] 37 | }, 38 | { 39 | "cell_type": "code", 40 | "execution_count": 51, 41 | "metadata": { 42 | "collapsed": false 43 | }, 44 | "outputs": [ 45 | { 46 | "name": "stdout", 47 | "output_type": "stream", 48 | "text": [ 49 | "Populating the interactive namespace from numpy and matplotlib\n" 50 | ] 51 | }, 52 | { 53 | "name": "stderr", 54 | "output_type": "stream", 55 | "text": [ 56 | "WARNING: pylab import has clobbered these variables: ['clf', 'permutation']\n", 57 | "`%matplotlib` prevents importing * from pylab and numpy\n" 58 | ] 59 | } 60 | ], 61 | "source": [ 62 | "%pylab inline\n", 63 | "import pickle\n", 64 | "from os import listdir, path\n", 65 | "import numpy as np\n", 66 | "from sklearn import svm, metrics\n", 67 | "\n", 68 | "ROBOT_POSE_DATA_DIR = 'robot_pose_data'" 69 | ] 70 | }, 71 | { 72 | "cell_type": "code", 73 | "execution_count": 52, 74 | "metadata": { 75 | "collapsed": false 76 | }, 77 | "outputs": [ 78 | { 79 | "name": "stdout", 80 | "output_type": "stream", 81 | "text": [ 82 | "['Frog', 'HeadBack', 'Left', 'Knee', 'Crouch', 'Back', 'Belly', 'Right', 'Sit', 'Stand', 'StandInit']\n" 83 | ] 84 | } 85 | ], 86 | "source": [ 87 | "classes = listdir(ROBOT_POSE_DATA_DIR)\n", 88 | "print classes" 89 | ] 90 | }, 91 | { 92 | "cell_type": "code", 93 | "execution_count": 84, 94 | "metadata": { 95 | "collapsed": true 96 | }, 97 | "outputs": [], 98 | "source": [ 99 | "def load_pose_data(i):\n", 100 | " '''load pose data from file'''\n", 101 | " data = []\n", 102 | " target = []\n", 103 | " # YOUR CODE HERE\n", 104 | " \n", 105 | " filename = path.join(ROBOT_POSE_DATA_DIR, classes[i])\n", 106 | " data = pickle.load(open(filename, 'rb'))\n", 107 | " target = [i] * len(data)\n", 108 | " return data, target" 109 | ] 110 | }, 111 | { 112 | "cell_type": "code", 113 | "execution_count": 61, 114 | "metadata": { 115 | "collapsed": false 116 | }, 117 | "outputs": [ 118 | { 119 | "name": "stdout", 120 | "output_type": "stream", 121 | "text": [ 122 | "total number of data 200\n" 123 | ] 124 | } 125 | ], 126 | "source": [ 127 | "# load all the data\n", 128 | "all_data = []\n", 129 | "all_target = []\n", 130 | "# YOUR CODE HERE\n", 131 | "\n", 132 | "print 'total number of data', len(all_data)" 133 | ] 134 | }, 135 | { 136 | "cell_type": "code", 137 | "execution_count": 86, 138 | "metadata": { 139 | "collapsed": false 140 | }, 141 | "outputs": [], 142 | "source": [ 143 | "# shuffule data\n", 144 | "permutation = np.random.permutation(len(all_data))\n", 145 | "n_training_data = int(len(all_data) * 0.7)\n", 146 | "training_data = permutation[:n_training_data]" 147 | ] 148 | }, 149 | { 150 | "cell_type": "markdown", 151 | "metadata": {}, 152 | "source": [ 153 | "## 3. Learn on training data\n", 154 | "\n", 155 | "In scikit-learn, an estimator for classification is a Python object that implements the methods fit(X, y) and predict(T). An example of an estimator is the class sklearn.svm.SVC that implements support vector classification." 156 | ] 157 | }, 158 | { 159 | "cell_type": "code", 160 | "execution_count": 56, 161 | "metadata": { 162 | "collapsed": false 163 | }, 164 | "outputs": [], 165 | "source": [ 166 | "clf = svm.SVC(gamma=0.001, C=100.)" 167 | ] 168 | }, 169 | { 170 | "cell_type": "markdown", 171 | "metadata": {}, 172 | "source": [ 173 | "### learning" 174 | ] 175 | }, 176 | { 177 | "cell_type": "code", 178 | "execution_count": 57, 179 | "metadata": { 180 | "collapsed": false 181 | }, 182 | "outputs": [ 183 | { 184 | "data": { 185 | "text/plain": [ 186 | "SVC(C=100.0, cache_size=200, class_weight=None, coef0=0.0, degree=3,\n", 187 | " gamma=0.001, kernel='rbf', max_iter=-1, probability=False,\n", 188 | " random_state=None, shrinking=True, tol=0.001, verbose=False)" 189 | ] 190 | }, 191 | "execution_count": 57, 192 | "metadata": {}, 193 | "output_type": "execute_result" 194 | } 195 | ], 196 | "source": [ 197 | "# YOUR CODE HERE" 198 | ] 199 | }, 200 | { 201 | "cell_type": "markdown", 202 | "metadata": {}, 203 | "source": [ 204 | "### predicting" 205 | ] 206 | }, 207 | { 208 | "cell_type": "code", 209 | "execution_count": 58, 210 | "metadata": { 211 | "collapsed": false 212 | }, 213 | "outputs": [ 214 | { 215 | "data": { 216 | "text/plain": [ 217 | "(array([10]), 10)" 218 | ] 219 | }, 220 | "execution_count": 58, 221 | "metadata": {}, 222 | "output_type": "execute_result" 223 | } 224 | ], 225 | "source": [ 226 | "clf.predict(all_data[-1]), all_target[-1]" 227 | ] 228 | }, 229 | { 230 | "cell_type": "code", 231 | "execution_count": 81, 232 | "metadata": { 233 | "collapsed": false 234 | }, 235 | "outputs": [], 236 | "source": [ 237 | "def evaluate(expected, predicted):\n", 238 | " print(\"Classification report:\\n%s\\n\" % metrics.classification_report(expected, predicted))\n", 239 | "\n", 240 | " print(\"Confusion matrix:\\n%s\" % metrics.confusion_matrix(expected, predicted))" 241 | ] 242 | }, 243 | { 244 | "cell_type": "code", 245 | "execution_count": 82, 246 | "metadata": { 247 | "collapsed": false 248 | }, 249 | "outputs": [ 250 | { 251 | "name": "stdout", 252 | "output_type": "stream", 253 | "text": [ 254 | "Classification report:\n", 255 | " precision recall f1-score support\n", 256 | "\n", 257 | " 0 1.00 1.00 1.00 5\n", 258 | " 1 1.00 1.00 1.00 7\n", 259 | " 2 1.00 1.00 1.00 15\n", 260 | " 3 1.00 1.00 1.00 5\n", 261 | " 4 1.00 1.00 1.00 20\n", 262 | " 5 1.00 1.00 1.00 6\n", 263 | " 6 1.00 1.00 1.00 8\n", 264 | " 7 1.00 1.00 1.00 7\n", 265 | " 8 1.00 1.00 1.00 18\n", 266 | " 9 1.00 1.00 1.00 8\n", 267 | " 10 1.00 1.00 1.00 41\n", 268 | "\n", 269 | "avg / total 1.00 1.00 1.00 140\n", 270 | "\n", 271 | "\n", 272 | "Confusion matrix:\n", 273 | "[[ 5 0 0 0 0 0 0 0 0 0 0]\n", 274 | " [ 0 7 0 0 0 0 0 0 0 0 0]\n", 275 | " [ 0 0 15 0 0 0 0 0 0 0 0]\n", 276 | " [ 0 0 0 5 0 0 0 0 0 0 0]\n", 277 | " [ 0 0 0 0 20 0 0 0 0 0 0]\n", 278 | " [ 0 0 0 0 0 6 0 0 0 0 0]\n", 279 | " [ 0 0 0 0 0 0 8 0 0 0 0]\n", 280 | " [ 0 0 0 0 0 0 0 7 0 0 0]\n", 281 | " [ 0 0 0 0 0 0 0 0 18 0 0]\n", 282 | " [ 0 0 0 0 0 0 0 0 0 8 0]\n", 283 | " [ 0 0 0 0 0 0 0 0 0 0 41]]\n" 284 | ] 285 | } 286 | ], 287 | "source": [ 288 | "expected = []\n", 289 | "predicted = []\n", 290 | "# YOUR CODE HERE\n", 291 | "\n", 292 | "evaluate(expected, predicted)" 293 | ] 294 | }, 295 | { 296 | "cell_type": "markdown", 297 | "metadata": {}, 298 | "source": [ 299 | "## 4. Evaluate on the test data" 300 | ] 301 | }, 302 | { 303 | "cell_type": "code", 304 | "execution_count": 83, 305 | "metadata": { 306 | "collapsed": false 307 | }, 308 | "outputs": [ 309 | { 310 | "name": "stdout", 311 | "output_type": "stream", 312 | "text": [ 313 | "Classification report:\n", 314 | " precision recall f1-score support\n", 315 | "\n", 316 | " 0 1.00 1.00 1.00 5\n", 317 | " 1 1.00 1.00 1.00 3\n", 318 | " 2 1.00 1.00 1.00 5\n", 319 | " 3 1.00 1.00 1.00 5\n", 320 | " 4 0.91 1.00 0.95 10\n", 321 | " 5 1.00 1.00 1.00 4\n", 322 | " 6 1.00 1.00 1.00 2\n", 323 | " 7 1.00 0.75 0.86 4\n", 324 | " 8 1.00 1.00 1.00 8\n", 325 | " 9 1.00 1.00 1.00 3\n", 326 | " 10 1.00 1.00 1.00 11\n", 327 | "\n", 328 | "avg / total 0.98 0.98 0.98 60\n", 329 | "\n", 330 | "\n", 331 | "Confusion matrix:\n", 332 | "[[ 5 0 0 0 0 0 0 0 0 0 0]\n", 333 | " [ 0 3 0 0 0 0 0 0 0 0 0]\n", 334 | " [ 0 0 5 0 0 0 0 0 0 0 0]\n", 335 | " [ 0 0 0 5 0 0 0 0 0 0 0]\n", 336 | " [ 0 0 0 0 10 0 0 0 0 0 0]\n", 337 | " [ 0 0 0 0 0 4 0 0 0 0 0]\n", 338 | " [ 0 0 0 0 0 0 2 0 0 0 0]\n", 339 | " [ 0 0 0 0 1 0 0 3 0 0 0]\n", 340 | " [ 0 0 0 0 0 0 0 0 8 0 0]\n", 341 | " [ 0 0 0 0 0 0 0 0 0 3 0]\n", 342 | " [ 0 0 0 0 0 0 0 0 0 0 11]]\n" 343 | ] 344 | } 345 | ], 346 | "source": [ 347 | "expected = []\n", 348 | "predicted = []\n", 349 | "# YOUR CODE HERE\n", 350 | "\n", 351 | "evaluate(expected, predicted)" 352 | ] 353 | }, 354 | { 355 | "cell_type": "markdown", 356 | "metadata": {}, 357 | "source": [ 358 | "## 5. Deploy to the real system\n", 359 | "\n", 360 | "We can simple use `pickle` module to serialize the trained classifier." 361 | ] 362 | }, 363 | { 364 | "cell_type": "code", 365 | "execution_count": 68, 366 | "metadata": { 367 | "collapsed": false 368 | }, 369 | "outputs": [], 370 | "source": [ 371 | "import pickle\n", 372 | "ROBOT_POSE_CLF = 'robot_pose.pkl'\n", 373 | "pickle.dump(clf, open(ROBOT_POSE_CLF, 'wb'))" 374 | ] 375 | }, 376 | { 377 | "cell_type": "markdown", 378 | "metadata": {}, 379 | "source": [ 380 | "Then, in the application we can load the trained classifier again." 381 | ] 382 | }, 383 | { 384 | "cell_type": "code", 385 | "execution_count": 71, 386 | "metadata": { 387 | "collapsed": false 388 | }, 389 | "outputs": [ 390 | { 391 | "data": { 392 | "text/plain": [ 393 | "(array([10]), 10)" 394 | ] 395 | }, 396 | "execution_count": 71, 397 | "metadata": {}, 398 | "output_type": "execute_result" 399 | } 400 | ], 401 | "source": [ 402 | "clf2 = pickle.load(open(ROBOT_POSE_CLF))\n", 403 | "clf2.predict(all_data[-1]), all_target[-1]" 404 | ] 405 | }, 406 | { 407 | "cell_type": "code", 408 | "execution_count": null, 409 | "metadata": { 410 | "collapsed": true 411 | }, 412 | "outputs": [], 413 | "source": [] 414 | } 415 | ], 416 | "metadata": { 417 | "kernelspec": { 418 | "display_name": "Python 2", 419 | "language": "python", 420 | "name": "python2" 421 | }, 422 | "language_info": { 423 | "codemirror_mode": { 424 | "name": "ipython", 425 | "version": 2 426 | }, 427 | "file_extension": ".py", 428 | "mimetype": "text/x-python", 429 | "name": "python", 430 | "nbconvert_exporter": "python", 431 | "pygments_lexer": "ipython2", 432 | "version": "2.7.12" 433 | }, 434 | "widgets": { 435 | "state": {}, 436 | "version": "1.0.0" 437 | } 438 | }, 439 | "nbformat": 4, 440 | "nbformat_minor": 0 441 | } 442 | -------------------------------------------------------------------------------- /joint_control/robot_pose_data/StandInit: -------------------------------------------------------------------------------- 1 | (lp0 2 | (lp1 3 | F4.1961669921875e-05 4 | aF-0.007627964019775391 5 | aF-0.2530679702758789 6 | aF0.9004161357879639 7 | aF4.1961669921875e-05 8 | aF-0.007627964019775391 9 | aF-0.5397986173629761 10 | aF0.9572582244873047 11 | aF0.007095034699887037 12 | aF-0.01821630820631981 13 | aa(lp2 14 | F4.1961669921875e-05 15 | aF-0.007627964019775391 16 | aF-0.2530679702758789 17 | aF0.9004161357879639 18 | aF4.1961669921875e-05 19 | aF-0.007627964019775391 20 | aF-0.5397986173629761 21 | aF0.9587922096252441 22 | aF0.007670100312680006 23 | aF-0.018407996743917465 24 | aa(lp3 25 | F4.1961669921875e-05 26 | aF-0.007627964019775391 27 | aF-0.2530679702758789 28 | aF0.9004161357879639 29 | aF4.1961669921875e-05 30 | aF-0.007627964019775391 31 | aF-0.5382646322250366 32 | aF0.9572582244873047 33 | aF0.0046021300368011 34 | aF-0.01572340354323387 35 | aa(lp4 36 | F4.1961669921875e-05 37 | aF-0.007627964019775391 38 | aF-0.2530679702758789 39 | aF0.9004161357879639 40 | aF4.1961669921875e-05 41 | aF-0.007627964019775391 42 | aF-0.5382646322250366 43 | aF0.9572582244873047 44 | aF0.00575273809954524 45 | aF-0.018791373819112778 46 | aa(lp5 47 | F4.1961669921875e-05 48 | aF-0.007627964019775391 49 | aF-0.2530679702758789 50 | aF0.9004161357879639 51 | aF4.1961669921875e-05 52 | aF-0.007627964019775391 53 | aF-0.5382646322250366 54 | aF0.9572582244873047 55 | aF0.005368884187191725 56 | aF-0.021284278482198715 57 | aa(lp6 58 | F4.1961669921875e-05 59 | aF-0.007627964019775391 60 | aF-0.2530679702758789 61 | aF0.9004161357879639 62 | aF4.1961669921875e-05 63 | aF-0.007627964019775391 64 | aF-0.5397986173629761 65 | aF0.9572582244873047 66 | aF0.006327803712338209 67 | aF-0.018024619668722153 68 | aa(lp7 69 | F4.1961669921875e-05 70 | aF-0.007627964019775391 71 | aF-0.2530679702758789 72 | aF0.9004161357879639 73 | aF4.1961669921875e-05 74 | aF-0.007627964019775391 75 | aF-0.5397986173629761 76 | aF0.9572582244873047 77 | aF0.008629020303487778 78 | aF-0.01936691626906395 79 | aa(lp8 80 | F4.1961669921875e-05 81 | aF-0.007627964019775391 82 | aF-0.2530679702758789 83 | aF0.9004161357879639 84 | aF4.1961669921875e-05 85 | aF-0.007627964019775391 86 | aF-0.5397986173629761 87 | aF0.9572582244873047 88 | aF0.006711180787533522 89 | aF-0.018407996743917465 90 | aa(lp9 91 | F4.1961669921875e-05 92 | aF-0.007627964019775391 93 | aF-0.2530679702758789 94 | aF0.9004161357879639 95 | aF4.1961669921875e-05 96 | aF-0.007627964019775391 97 | aF-0.5382646322250366 98 | aF0.9572582244873047 99 | aF0.00575273809954524 100 | aF-0.018407996743917465 101 | aa(lp10 102 | F4.1961669921875e-05 103 | aF-0.007627964019775391 104 | aF-0.2530679702758789 105 | aF0.9004161357879639 106 | aF4.1961669921875e-05 107 | aF-0.007627964019775391 108 | aF-0.5397986173629761 109 | aF0.9572582244873047 110 | aF0.006711180787533522 111 | aF-0.01744907721877098 112 | aa(lp11 113 | F4.1961669921875e-05 114 | aF-0.007627964019775391 115 | aF-0.2530679702758789 116 | aF0.9004161357879639 117 | aF4.1961669921875e-05 118 | aF-0.007627964019775391 119 | aF-0.5382646322250366 120 | aF0.9572582244873047 121 | aF0.0072867232374846935 122 | aF-0.017257388681173325 123 | aa(lp12 124 | F4.1961669921875e-05 125 | aF-0.007627964019775391 126 | aF-0.2530679702758789 127 | aF0.9004161357879639 128 | aF4.1961669921875e-05 129 | aF-0.007627964019775391 130 | aF-0.5382646322250366 131 | aF0.9572582244873047 132 | aF0.004793818574398756 133 | aF-0.01936691626906395 134 | aa(lp13 135 | F4.1961669921875e-05 136 | aF-0.007627964019775391 137 | aF-0.2530679702758789 138 | aF0.9004161357879639 139 | aF4.1961669921875e-05 140 | aF-0.007627964019775391 141 | aF-0.5382646322250366 142 | aF0.9572582244873047 143 | aF0.00747841177508235 144 | aF-0.022434409707784653 145 | aa(lp14 146 | F4.1961669921875e-05 147 | aF-0.007627964019775391 148 | aF-0.2530679702758789 149 | aF0.9004161357879639 150 | aF4.1961669921875e-05 151 | aF-0.007627964019775391 152 | aF-0.5397986173629761 153 | aF0.9572582244873047 154 | aF0.002876456594094634 155 | aF-0.01936691626906395 156 | aa(lp15 157 | F4.1961669921875e-05 158 | aF-0.007627964019775391 159 | aF-0.2530679702758789 160 | aF0.9004161357879639 161 | aF4.1961669921875e-05 162 | aF-0.007627964019775391 163 | aF-0.5397986173629761 164 | aF0.9572582244873047 165 | aF0.00575273809954524 166 | aF-0.0164906345307827 167 | aa(lp16 168 | F4.1961669921875e-05 169 | aF-0.007627964019775391 170 | aF-0.2530679702758789 171 | aF0.9004161357879639 172 | aF4.1961669921875e-05 173 | aF-0.007627964019775391 174 | aF-0.5397986173629761 175 | aF0.9572582244873047 176 | aF0.00575273809954524 177 | aF-0.01936691626906395 178 | aa(lp17 179 | F4.1961669921875e-05 180 | aF-0.007627964019775391 181 | aF-0.2530679702758789 182 | aF0.9004161357879639 183 | aF4.1961669921875e-05 184 | aF-0.007627964019775391 185 | aF-0.5397986173629761 186 | aF0.9572582244873047 187 | aF0.00575273809954524 188 | aF-0.0164906345307827 189 | aa(lp18 190 | F4.1961669921875e-05 191 | aF-0.007627964019775391 192 | aF-0.2530679702758789 193 | aF0.9004161357879639 194 | aF4.1961669921875e-05 195 | aF-0.007627964019775391 196 | aF-0.5397986173629761 197 | aF0.9572582244873047 198 | aF0.00575273809954524 199 | aF-0.015531715005636215 200 | aa(lp19 201 | F4.1961669921875e-05 202 | aF-0.007627964019775391 203 | aF-0.2530679702758789 204 | aF0.9019501209259033 205 | aF4.1961669921875e-05 206 | aF-0.007627964019775391 207 | aF-0.5382646322250366 208 | aF0.9572582244873047 209 | aF0.01016300544142723 210 | aF-0.019750293344259262 211 | aa(lp20 212 | F4.1961669921875e-05 213 | aF-0.007627964019775391 214 | aF-0.2530679702758789 215 | aF0.9004161357879639 216 | aF4.1961669921875e-05 217 | aF-0.007627964019775391 218 | aF-0.5397986173629761 219 | aF0.9572582244873047 220 | aF0.008629020303487778 221 | aF-0.02032535895705223 222 | aa(lp21 223 | F4.1961669921875e-05 224 | aF-0.007627964019775391 225 | aF-0.2530679702758789 226 | aF0.9004161357879639 227 | aF4.1961669921875e-05 228 | aF-0.007627964019775391 229 | aF-0.5382646322250366 230 | aF0.9572582244873047 231 | aF0.004218752961605787 232 | aF-0.016682323068380356 233 | aa(lp22 234 | F4.1961669921875e-05 235 | aF-0.007627964019775391 236 | aF-0.2530679702758789 237 | aF0.9004161357879639 238 | aF4.1961669921875e-05 239 | aF-0.007627964019775391 240 | aF-0.5382646322250366 241 | aF0.9572582244873047 242 | aF0.008629020303487778 243 | aF-0.018407996743917465 244 | aa(lp23 245 | F4.1961669921875e-05 246 | aF-0.007627964019775391 247 | aF-0.2530679702758789 248 | aF0.9004161357879639 249 | aF4.1961669921875e-05 250 | aF-0.007627964019775391 251 | aF-0.5397986173629761 252 | aF0.9572582244873047 253 | aF0.008629020303487778 254 | aF-0.0164906345307827 255 | aa(lp24 256 | F4.1961669921875e-05 257 | aF-0.007627964019775391 258 | aF-0.2530679702758789 259 | aF0.9004161357879639 260 | aF4.1961669921875e-05 261 | aF-0.007627964019775391 262 | aF-0.5382646322250366 263 | aF0.9572582244873047 264 | aF0.00575273809954524 265 | aF-0.018407996743917465 266 | aa(lp25 267 | F4.1961669921875e-05 268 | aF-0.007627964019775391 269 | aF-0.2530679702758789 270 | aF0.9004161357879639 271 | aF4.1961669921875e-05 272 | aF-0.007627964019775391 273 | aF-0.5382646322250366 274 | aF0.9572582244873047 275 | aF0.004793818574398756 276 | aF-0.01994198188185692 277 | aa(lp26 278 | F4.1961669921875e-05 279 | aF-0.007627964019775391 280 | aF-0.2530679702758789 281 | aF0.9004161357879639 282 | aF4.1961669921875e-05 283 | aF-0.007627964019775391 284 | aF-0.5397986173629761 285 | aF0.9572582244873047 286 | aF0.007670100312680006 287 | aF-0.01744907721877098 288 | aa(lp27 289 | F4.1961669921875e-05 290 | aF-0.007627964019775391 291 | aF-0.2530679702758789 292 | aF0.9004161357879639 293 | aF4.1961669921875e-05 294 | aF-0.007627964019775391 295 | aF-0.5382646322250366 296 | aF0.9572582244873047 297 | aF0.004793818574398756 298 | aF-0.020708736032247543 299 | aa(lp28 300 | F4.1961669921875e-05 301 | aF-0.007627964019775391 302 | aF-0.2530679702758789 303 | aF0.9004161357879639 304 | aF4.1961669921875e-05 305 | aF-0.007627964019775391 306 | aF-0.5397986173629761 307 | aF0.9572582244873047 308 | aF0.004027064424008131 309 | aF-0.019750293344259262 310 | aa(lp29 311 | F4.1961669921875e-05 312 | aF-0.007627964019775391 313 | aF-0.2530679702758789 314 | aF0.9004161357879639 315 | aF4.1961669921875e-05 316 | aF-0.007627964019775391 317 | aF-0.5397986173629761 318 | aF0.9572582244873047 319 | aF0.00575273809954524 320 | aF-0.01744907721877098 321 | aa(lp30 322 | F4.1961669921875e-05 323 | aF-0.007627964019775391 324 | aF-0.2530679702758789 325 | aF0.9004161357879639 326 | aF4.1961669921875e-05 327 | aF-0.007627964019775391 328 | aF-0.5382646322250366 329 | aF0.9572582244873047 330 | aF0.006136115174740553 331 | aF-0.017257388681173325 332 | aa(lp31 333 | F-0.022968053817749023 334 | aF-0.024502038955688477 335 | aF-0.23772811889648438 336 | aF0.8958139419555664 337 | aF-0.022968053817749023 338 | aF-0.02143406867980957 339 | aF-0.5152546167373657 340 | aF0.941917896270752 341 | aF-0.0339391864836216 342 | aF0.07631523162126541 343 | aa(lp32 344 | F-0.19324207305908203 345 | aF0.1304318904876709 346 | aF-0.4693620204925537 347 | aF0.9050180912017822 348 | aF-0.19324207305908203 349 | aF0.06753802299499512 350 | aF-0.16703666746616364 351 | aF0.9127721786499023 352 | aF-0.003834549570456147 353 | aF0.018215958029031754 354 | aa(lp33 355 | F-0.19324207305908203 356 | aF0.1304318904876709 357 | aF-0.47089600563049316 358 | aF0.9065520763397217 359 | aF-0.19324207305908203 360 | aF0.06753802299499512 361 | aF-0.16703666746616364 362 | aF0.9127721786499023 363 | aF-0.00402671517804265 364 | aF0.018599335104227066 365 | aa(lp34 366 | F-0.19324207305908203 367 | aF0.1304318904876709 368 | aF-0.4693620204925537 369 | aF0.9065520763397217 370 | aF-0.19324207305908203 371 | aF0.06753802299499512 372 | aF-0.16703666746616364 373 | aF0.9127721786499023 374 | aF-0.004793469328433275 375 | aF0.019366566091775894 376 | aa(lp35 377 | F-0.19324207305908203 378 | aF0.1304318904876709 379 | aF-0.47089600563049316 380 | aF0.9065520763397217 381 | aF-0.19324207305908203 382 | aF0.06753802299499512 383 | aF-0.1685706526041031 384 | aF0.9112381935119629 385 | aF-0.0049851578660309315 386 | aF0.019366566091775894 387 | aa(lp36 388 | F-0.19324207305908203 389 | aF0.12889790534973145 390 | aF-0.4693620204925537 391 | aF0.9065520763397217 392 | aF-0.19324207305908203 393 | aF0.06907200813293457 394 | aF-0.1685706526041031 395 | aF0.9127721786499023 396 | aF-0.002876106882467866 397 | aF0.017448727041482925 398 | aa(lp37 399 | F-0.19324207305908203 400 | aF0.1304318904876709 401 | aF-0.4693620204925537 402 | aF0.9065520763397217 403 | aF-0.19324207305908203 404 | aF0.06753802299499512 405 | aF-0.16703666746616364 406 | aF0.9112381935119629 407 | aF-0.003834549570456147 408 | aF0.020325008779764175 409 | aa(lp38 410 | F-0.19324207305908203 411 | aF0.1304318904876709 412 | aF-0.4693620204925537 413 | aF0.9065520763397217 414 | aF-0.19324207305908203 415 | aF0.06753802299499512 416 | aF-0.16703666746616364 417 | aF0.9112381935119629 418 | aF-0.003834549570456147 419 | aF0.02224237099289894 420 | aa(lp39 421 | F-0.19324207305908203 422 | aF0.12889790534973145 423 | aF-0.4693620204925537 424 | aF0.9065520763397217 425 | aF-0.19324207305908203 426 | aF0.06753802299499512 427 | aF-0.16703666746616364 428 | aF0.9127721786499023 429 | aF-0.006710831541568041 430 | aF0.017448727041482925 431 | aa(lp40 432 | F-0.19324207305908203 433 | aF0.12889790534973145 434 | aF-0.47089600563049316 435 | aF0.9065520763397217 436 | aF-0.19324207305908203 437 | aF0.06753802299499512 438 | aF-0.16703666746616364 439 | aF0.9112381935119629 440 | aF-0.0019171873573213816 441 | aF0.017448727041482925 442 | aa(lp41 443 | F-0.19324207305908203 444 | aF0.12889790534973145 445 | aF-0.4693620204925537 446 | aF0.9065520763397217 447 | aF-0.19324207305908203 448 | aF0.06753802299499512 449 | aF-0.16703666746616364 450 | aF0.9112381935119629 451 | aF-0.0019171873573213816 452 | aF0.022434059530496597 453 | aa(lp42 454 | F-0.19324207305908203 455 | aF0.1304318904876709 456 | aF-0.4693620204925537 457 | aF0.9065520763397217 458 | aF-0.19324207305908203 459 | aF0.06753802299499512 460 | aF-0.16703666746616364 461 | aF0.9127721786499023 462 | aF-0.0011504332069307566 463 | aF0.016490284353494644 464 | aa(lp43 465 | F-0.19477605819702148 466 | aF0.12889790534973145 467 | aF-0.4693620204925537 468 | aF0.9065520763397217 469 | aF-0.19477605819702148 470 | aF0.06753802299499512 471 | aF-0.16703666746616364 472 | aF0.9127721786499023 473 | aF-0.0009587446693331003 474 | aF0.020325008779764175 475 | aa(lp44 476 | F-0.19324207305908203 477 | aF0.12889790534973145 478 | aF-0.4693620204925537 479 | aF0.9065520763397217 480 | aF-0.19324207305908203 481 | aF0.06753802299499512 482 | aF-0.16703666746616364 483 | aF0.9112381935119629 484 | aF-0.003067795420065522 485 | aF0.0166819728910923 486 | aa(lp45 487 | F-0.19477605819702148 488 | aF0.1304318904876709 489 | aF-0.4693620204925537 490 | aF0.9065520763397217 491 | aF-0.19477605819702148 492 | aF0.06753802299499512 493 | aF-0.16703666746616364 494 | aF0.9112381935119629 495 | aF-0.003642861032858491 496 | aF0.019174400717020035 497 | aa(lp46 498 | F-0.19477605819702148 499 | aF0.12889790534973145 500 | aF-0.47089600563049316 501 | aF0.9065520763397217 502 | aF-0.19477605819702148 503 | aF0.06907200813293457 504 | aF-0.1685706526041031 505 | aF0.9112381935119629 506 | aF-0.00575238885357976 507 | aF0.022434059530496597 508 | aa(lp47 509 | F-0.19477605819702148 510 | aF0.1304318904876709 511 | aF-0.4693620204925537 512 | aF0.9065520763397217 513 | aF-0.19477605819702148 514 | aF0.06753802299499512 515 | aF-0.16703666746616364 516 | aF0.9127721786499023 517 | aF-0.00575238885357976 518 | aF0.02013332024216652 519 | aa(lp48 520 | F-0.19324207305908203 521 | aF0.1304318904876709 522 | aF-0.47089600563049316 523 | aF0.9065520763397217 524 | aF-0.19324207305908203 525 | aF0.06753802299499512 526 | aF-0.16703666746616364 527 | aF0.9127721786499023 528 | aF-0.0019171873573213816 529 | aF0.019366566091775894 530 | aa(lp49 531 | F-0.19477605819702148 532 | aF0.1304318904876709 533 | aF-0.47089600563049316 534 | aF0.9065520763397217 535 | aF-0.19477605819702148 536 | aF0.06753802299499512 537 | aF-0.16703666746616364 538 | aF0.9127721786499023 539 | aF-0.002876106882467866 540 | aF0.01840764656662941 541 | aa(lp50 542 | F-0.027570009231567383 543 | aF0.004643917083740234 544 | aF-0.5736739635467529 545 | aF0.9847860336303711 546 | aF-0.027570009231567383 547 | aF-0.004559993743896484 548 | aF-0.2774845361709595 549 | aF0.9173741340637207 550 | aF-0.011696640402078629 551 | aF0.044868770986795425 552 | aa(lp51 553 | F-0.029103994369506836 554 | aF0.004643917083740234 555 | aF-0.5736739635467529 556 | aF0.9847860336303711 557 | aF-0.027570009231567383 558 | aF-0.004559993743896484 559 | aF-0.2774845361709595 560 | aF0.9173741340637207 561 | aF-0.013614002615213394 562 | aF0.040841881185770035 563 | aa(lp52 564 | F-0.2469320297241211 565 | aF0.12582993507385254 566 | aF-0.2868161201477051 567 | aF0.9955241680145264 568 | aF-0.2469320297241211 569 | aF-0.12421202659606934 570 | aF-0.30049455165863037 571 | aF1.0109481811523438 572 | aF0.015148337930440903 573 | aF0.11869174987077713 574 | aa. -------------------------------------------------------------------------------- /software_installation/python_basic.ipynb: -------------------------------------------------------------------------------- 1 | { 2 | "metadata": { 3 | "name": "" 4 | }, 5 | "nbformat": 3, 6 | "nbformat_minor": 0, 7 | "worksheets": [ 8 | { 9 | "cells": [ 10 | { 11 | "cell_type": "heading", 12 | "level": 1, 13 | "metadata": { 14 | "slideshow": { 15 | "slide_type": "slide" 16 | } 17 | }, 18 | "source": [ 19 | "Python Baisc" 20 | ] 21 | }, 22 | { 23 | "cell_type": "heading", 24 | "level": 2, 25 | "metadata": { 26 | "slideshow": { 27 | "slide_type": "slide" 28 | } 29 | }, 30 | "source": [ 31 | "Math" 32 | ] 33 | }, 34 | { 35 | "cell_type": "code", 36 | "collapsed": false, 37 | "input": [ 38 | "2 + 2" 39 | ], 40 | "language": "python", 41 | "metadata": { 42 | "slideshow": { 43 | "slide_type": "slide" 44 | } 45 | }, 46 | "outputs": [ 47 | { 48 | "metadata": {}, 49 | "output_type": "pyout", 50 | "prompt_number": 1, 51 | "text": [ 52 | "4" 53 | ] 54 | } 55 | ], 56 | "prompt_number": 1 57 | }, 58 | { 59 | "cell_type": "code", 60 | "collapsed": false, 61 | "input": [ 62 | "(1 - 2*3) / 4" 63 | ], 64 | "language": "python", 65 | "metadata": {}, 66 | "outputs": [ 67 | { 68 | "metadata": {}, 69 | "output_type": "pyout", 70 | "prompt_number": 2, 71 | "text": [ 72 | "-2" 73 | ] 74 | } 75 | ], 76 | "prompt_number": 2 77 | }, 78 | { 79 | "cell_type": "code", 80 | "collapsed": false, 81 | "input": [ 82 | "7/3." 83 | ], 84 | "language": "python", 85 | "metadata": {}, 86 | "outputs": [ 87 | { 88 | "metadata": {}, 89 | "output_type": "pyout", 90 | "prompt_number": 3, 91 | "text": [ 92 | "2.3333333333333335" 93 | ] 94 | } 95 | ], 96 | "prompt_number": 3 97 | }, 98 | { 99 | "cell_type": "code", 100 | "collapsed": false, 101 | "input": [ 102 | "7/3" 103 | ], 104 | "language": "python", 105 | "metadata": {}, 106 | "outputs": [ 107 | { 108 | "metadata": {}, 109 | "output_type": "pyout", 110 | "prompt_number": 4, 111 | "text": [ 112 | "2" 113 | ] 114 | } 115 | ], 116 | "prompt_number": 4 117 | }, 118 | { 119 | "cell_type": "code", 120 | "collapsed": false, 121 | "input": [ 122 | "from __future__ import division\n", 123 | "7 / 3" 124 | ], 125 | "language": "python", 126 | "metadata": {}, 127 | "outputs": [ 128 | { 129 | "metadata": {}, 130 | "output_type": "pyout", 131 | "prompt_number": 5, 132 | "text": [ 133 | "2.3333333333333335" 134 | ] 135 | } 136 | ], 137 | "prompt_number": 5 138 | }, 139 | { 140 | "cell_type": "code", 141 | "collapsed": false, 142 | "input": [ 143 | "2**10" 144 | ], 145 | "language": "python", 146 | "metadata": {}, 147 | "outputs": [ 148 | { 149 | "metadata": {}, 150 | "output_type": "pyout", 151 | "prompt_number": 7, 152 | "text": [ 153 | "1024" 154 | ] 155 | } 156 | ], 157 | "prompt_number": 7 158 | }, 159 | { 160 | "cell_type": "code", 161 | "collapsed": false, 162 | "input": [ 163 | "1024**0.5" 164 | ], 165 | "language": "python", 166 | "metadata": {}, 167 | "outputs": [] 168 | }, 169 | { 170 | "cell_type": "code", 171 | "collapsed": false, 172 | "input": [ 173 | "from math import sin, pi\n", 174 | "sin(pi)" 175 | ], 176 | "language": "python", 177 | "metadata": {}, 178 | "outputs": [ 179 | { 180 | "metadata": {}, 181 | "output_type": "pyout", 182 | "prompt_number": 6, 183 | "text": [ 184 | "1.2246467991473532e-16" 185 | ] 186 | } 187 | ], 188 | "prompt_number": 6 189 | }, 190 | { 191 | "cell_type": "code", 192 | "collapsed": false, 193 | "input": [ 194 | "width = 3\n", 195 | "length = 4\n", 196 | "area = width * length\n", 197 | "area" 198 | ], 199 | "language": "python", 200 | "metadata": {}, 201 | "outputs": [ 202 | { 203 | "metadata": {}, 204 | "output_type": "pyout", 205 | "prompt_number": 8, 206 | "text": [ 207 | "12" 208 | ] 209 | } 210 | ], 211 | "prompt_number": 8 212 | }, 213 | { 214 | "cell_type": "heading", 215 | "level": 2, 216 | "metadata": {}, 217 | "source": [ 218 | "String" 219 | ] 220 | }, 221 | { 222 | "cell_type": "code", 223 | "collapsed": false, 224 | "input": [ 225 | "'Hello world!'" 226 | ], 227 | "language": "python", 228 | "metadata": {}, 229 | "outputs": [ 230 | { 231 | "metadata": {}, 232 | "output_type": "pyout", 233 | "prompt_number": 9, 234 | "text": [ 235 | "'Hello world!'" 236 | ] 237 | } 238 | ], 239 | "prompt_number": 9 240 | }, 241 | { 242 | "cell_type": "code", 243 | "collapsed": false, 244 | "input": [ 245 | "print \"Hello 'again'\"" 246 | ], 247 | "language": "python", 248 | "metadata": {}, 249 | "outputs": [ 250 | { 251 | "output_type": "stream", 252 | "stream": "stdout", 253 | "text": [ 254 | "Hello 'again'\n" 255 | ] 256 | } 257 | ], 258 | "prompt_number": 10 259 | }, 260 | { 261 | "cell_type": "code", 262 | "collapsed": false, 263 | "input": [ 264 | "hello = 'Hello'\n", 265 | "world = 'World'\n", 266 | "hello + world" 267 | ], 268 | "language": "python", 269 | "metadata": {}, 270 | "outputs": [ 271 | { 272 | "metadata": {}, 273 | "output_type": "pyout", 274 | "prompt_number": 12, 275 | "text": [ 276 | "'HelloWorld'" 277 | ] 278 | } 279 | ], 280 | "prompt_number": 12 281 | }, 282 | { 283 | "cell_type": "code", 284 | "collapsed": false, 285 | "input": [ 286 | "hello.upper()" 287 | ], 288 | "language": "python", 289 | "metadata": {}, 290 | "outputs": [ 291 | { 292 | "metadata": {}, 293 | "output_type": "pyout", 294 | "prompt_number": 13, 295 | "text": [ 296 | "'HELLO'" 297 | ] 298 | } 299 | ], 300 | "prompt_number": 13 301 | }, 302 | { 303 | "cell_type": "heading", 304 | "level": 2, 305 | "metadata": {}, 306 | "source": [ 307 | "List" 308 | ] 309 | }, 310 | { 311 | "cell_type": "code", 312 | "collapsed": false, 313 | "input": [ 314 | "days_of_the_week = [\"Sunday\",\"Monday\",\"Tuesday\",\"Wednesday\",\"Thursday\",\"Friday\",\"Saturday\"]" 315 | ], 316 | "language": "python", 317 | "metadata": {}, 318 | "outputs": [], 319 | "prompt_number": 14 320 | }, 321 | { 322 | "cell_type": "code", 323 | "collapsed": false, 324 | "input": [ 325 | "days_of_the_week[5]" 326 | ], 327 | "language": "python", 328 | "metadata": {}, 329 | "outputs": [ 330 | { 331 | "metadata": {}, 332 | "output_type": "pyout", 333 | "prompt_number": 15, 334 | "text": [ 335 | "'Friday'" 336 | ] 337 | } 338 | ], 339 | "prompt_number": 15 340 | }, 341 | { 342 | "cell_type": "code", 343 | "collapsed": false, 344 | "input": [ 345 | "days_of_the_week[-2]" 346 | ], 347 | "language": "python", 348 | "metadata": {}, 349 | "outputs": [ 350 | { 351 | "metadata": {}, 352 | "output_type": "pyout", 353 | "prompt_number": 16, 354 | "text": [ 355 | "'Friday'" 356 | ] 357 | } 358 | ], 359 | "prompt_number": 16 360 | }, 361 | { 362 | "cell_type": "code", 363 | "collapsed": false, 364 | "input": [ 365 | "[\"Friday\", 2014]" 366 | ], 367 | "language": "python", 368 | "metadata": {}, 369 | "outputs": [] 370 | }, 371 | { 372 | "cell_type": "code", 373 | "collapsed": false, 374 | "input": [ 375 | "nested_list = [0, 1, 2, [1, 3, 5, [2, 2, 2]]]\n", 376 | "nested_list" 377 | ], 378 | "language": "python", 379 | "metadata": {}, 380 | "outputs": [ 381 | { 382 | "metadata": {}, 383 | "output_type": "pyout", 384 | "prompt_number": 26, 385 | "text": [ 386 | "[0, 1, 2, [1, 3, 5, [2, 2, 2]]]" 387 | ] 388 | } 389 | ], 390 | "prompt_number": 26 391 | }, 392 | { 393 | "cell_type": "heading", 394 | "level": 3, 395 | "metadata": {}, 396 | "source": [ 397 | "Slicing" 398 | ] 399 | }, 400 | { 401 | "cell_type": "code", 402 | "collapsed": false, 403 | "input": [ 404 | "days_of_the_week[1:3]" 405 | ], 406 | "language": "python", 407 | "metadata": {}, 408 | "outputs": [ 409 | { 410 | "metadata": {}, 411 | "output_type": "pyout", 412 | "prompt_number": 17, 413 | "text": [ 414 | "['Monday', 'Tuesday']" 415 | ] 416 | } 417 | ], 418 | "prompt_number": 17 419 | }, 420 | { 421 | "cell_type": "code", 422 | "collapsed": false, 423 | "input": [ 424 | "days_of_the_week[4:]" 425 | ], 426 | "language": "python", 427 | "metadata": {}, 428 | "outputs": [] 429 | }, 430 | { 431 | "cell_type": "code", 432 | "collapsed": false, 433 | "input": [ 434 | "days_of_the_week[:3]" 435 | ], 436 | "language": "python", 437 | "metadata": {}, 438 | "outputs": [ 439 | { 440 | "metadata": {}, 441 | "output_type": "pyout", 442 | "prompt_number": 18, 443 | "text": [ 444 | "['Sunday', 'Monday', 'Tuesday']" 445 | ] 446 | } 447 | ], 448 | "prompt_number": 18 449 | }, 450 | { 451 | "cell_type": "code", 452 | "collapsed": false, 453 | "input": [ 454 | "hello[:-2]" 455 | ], 456 | "language": "python", 457 | "metadata": {}, 458 | "outputs": [ 459 | { 460 | "metadata": {}, 461 | "output_type": "pyout", 462 | "prompt_number": 19, 463 | "text": [ 464 | "'Hel'" 465 | ] 466 | } 467 | ], 468 | "prompt_number": 19 469 | }, 470 | { 471 | "cell_type": "heading", 472 | "level": 3, 473 | "metadata": {}, 474 | "source": [ 475 | "range" 476 | ] 477 | }, 478 | { 479 | "cell_type": "code", 480 | "collapsed": false, 481 | "input": [ 482 | "range(10)" 483 | ], 484 | "language": "python", 485 | "metadata": {}, 486 | "outputs": [ 487 | { 488 | "metadata": {}, 489 | "output_type": "pyout", 490 | "prompt_number": 20, 491 | "text": [ 492 | "[0, 1, 2, 3, 4, 5, 6, 7, 8, 9]" 493 | ] 494 | } 495 | ], 496 | "prompt_number": 20 497 | }, 498 | { 499 | "cell_type": "code", 500 | "collapsed": false, 501 | "input": [ 502 | "range(2,10)" 503 | ], 504 | "language": "python", 505 | "metadata": {}, 506 | "outputs": [ 507 | { 508 | "metadata": {}, 509 | "output_type": "pyout", 510 | "prompt_number": 21, 511 | "text": [ 512 | "[2, 3, 4, 5, 6, 7, 8, 9]" 513 | ] 514 | } 515 | ], 516 | "prompt_number": 21 517 | }, 518 | { 519 | "cell_type": "code", 520 | "collapsed": false, 521 | "input": [ 522 | "range(2,10,3)" 523 | ], 524 | "language": "python", 525 | "metadata": {}, 526 | "outputs": [ 527 | { 528 | "metadata": {}, 529 | "output_type": "pyout", 530 | "prompt_number": 22, 531 | "text": [ 532 | "[2, 5, 8]" 533 | ] 534 | } 535 | ], 536 | "prompt_number": 22 537 | }, 538 | { 539 | "cell_type": "code", 540 | "collapsed": false, 541 | "input": [ 542 | "help(len)" 543 | ], 544 | "language": "python", 545 | "metadata": {}, 546 | "outputs": [ 547 | { 548 | "output_type": "stream", 549 | "stream": "stdout", 550 | "text": [ 551 | "Help on built-in function len in module __builtin__:\n", 552 | "\n", 553 | "len(...)\n", 554 | " len(object) -> integer\n", 555 | " \n", 556 | " Return the number of items of a sequence or mapping.\n", 557 | "\n" 558 | ] 559 | } 560 | ], 561 | "prompt_number": 23 562 | }, 563 | { 564 | "cell_type": "code", 565 | "collapsed": false, 566 | "input": [ 567 | "len?" 568 | ], 569 | "language": "python", 570 | "metadata": {}, 571 | "outputs": [], 572 | "prompt_number": 24 573 | }, 574 | { 575 | "cell_type": "code", 576 | "collapsed": false, 577 | "input": [ 578 | "len(nested_list)" 579 | ], 580 | "language": "python", 581 | "metadata": {}, 582 | "outputs": [ 583 | { 584 | "metadata": {}, 585 | "output_type": "pyout", 586 | "prompt_number": 27, 587 | "text": [ 588 | "4" 589 | ] 590 | } 591 | ], 592 | "prompt_number": 27 593 | }, 594 | { 595 | "cell_type": "heading", 596 | "level": 2, 597 | "metadata": {}, 598 | "source": [ 599 | "Iteration, Indentation, and Blocks" 600 | ] 601 | }, 602 | { 603 | "cell_type": "code", 604 | "collapsed": false, 605 | "input": [ 606 | "for day in days_of_the_week:\n", 607 | " print day\n", 608 | " if day == 'Monday':\n", 609 | " print 'work'" 610 | ], 611 | "language": "python", 612 | "metadata": {}, 613 | "outputs": [ 614 | { 615 | "output_type": "stream", 616 | "stream": "stdout", 617 | "text": [ 618 | "Sunday\n", 619 | "Monday\n", 620 | "work\n", 621 | "Tuesday\n", 622 | "Wednesday\n", 623 | "Thursday\n", 624 | "Friday\n", 625 | "Saturday\n" 626 | ] 627 | } 628 | ], 629 | "prompt_number": 30 630 | }, 631 | { 632 | "cell_type": "heading", 633 | "level": 2, 634 | "metadata": {}, 635 | "source": [ 636 | "Function" 637 | ] 638 | }, 639 | { 640 | "cell_type": "code", 641 | "collapsed": false, 642 | "input": [ 643 | "def fact(n):\n", 644 | " '''this is doc string of fact'''\n", 645 | " if n <= 0:\n", 646 | " return 1\n", 647 | " return n*fact(n-1)" 648 | ], 649 | "language": "python", 650 | "metadata": {}, 651 | "outputs": [], 652 | "prompt_number": 32 653 | }, 654 | { 655 | "cell_type": "code", 656 | "collapsed": false, 657 | "input": [ 658 | "help(fact)" 659 | ], 660 | "language": "python", 661 | "metadata": {}, 662 | "outputs": [ 663 | { 664 | "output_type": "stream", 665 | "stream": "stdout", 666 | "text": [ 667 | "Help on function fact in module __main__:\n", 668 | "\n", 669 | "fact(n)\n", 670 | " this is doc string of fact\n", 671 | "\n" 672 | ] 673 | } 674 | ], 675 | "prompt_number": 33 676 | }, 677 | { 678 | "cell_type": "code", 679 | "collapsed": false, 680 | "input": [ 681 | "fact(10)" 682 | ], 683 | "language": "python", 684 | "metadata": {}, 685 | "outputs": [ 686 | { 687 | "metadata": {}, 688 | "output_type": "pyout", 689 | "prompt_number": 34, 690 | "text": [ 691 | "3628800" 692 | ] 693 | } 694 | ], 695 | "prompt_number": 34 696 | }, 697 | { 698 | "cell_type": "markdown", 699 | "metadata": {}, 700 | "source": [ 701 | "## Reference\n", 702 | "* [Introduction to Programming (using Python)](http://nbviewer.ipython.org/github/ehmatthes/intro_programming/blob/master/notebooks/index.ipynb)\n", 703 | "* [A gallery of interesting IPython Notebooks](https://github.com/ipython/ipython/wiki/A-gallery-of-interesting-IPython-Notebooks#scientific-computing-and-data-analysis-with-the-scipy-stack)\n", 704 | "* [Lecture 1 in scientific python lectures](http://nbviewer.ipython.org/github/jrjohansson/scientific-python-lectures/blob/master/Lecture-1-Introduction-to-Python-Programming.ipynb)" 705 | ] 706 | } 707 | ], 708 | "metadata": {} 709 | } 710 | ] 711 | } --------------------------------------------------------------------------------