In this notebook, we will show you the very basic way of controlling your robot using pypot. More precisely, we will see how to:
All examples we will be based on the robot Poppy, yet as detailed below you don't actually need the real robot as you can use a simulated version instead.
While you have access to other control layers (e.g. dynamixel low-level or defining your own controller), the method presented in this notebook should be the best one for most use cases.
Finally, in this notebook we will also show how you can seamlessly switch from controlling a real robot to controlling the simulated version in V-REP.
The Robot class in pypot provides different factories that can be used to easily instantiate it:
Robot in pypot are built using a configuration dictionary. This configuration defines which port to use, which motors are connected to each buses...
You can find Poppy's configuration file directly in the poppytools package:
In [1]:
import os
import poppytools
config_path = os.path.join(os.path.dirname(poppytools.__file__), 'configuration', 'poppy_config.json')
For details on what's inside those configuration files, please directly refer to pypot's documentation.
You can then easily instantiate your robot using the from_json factory (you should have plugged your Poppy to your computer at this point):
In [2]:
from pypot.robot import from_json
poppy = from_json(config_path)
If everything went well you should now be connected to the robot.
If you don't have a real robot, you can still play with the simulated version. You can connect pypot to the V-REP robotic simulator.
Please refer to this post for information on how to do this.
In [2]:
from pypot.vrep import from_vrep
import json
with open(config_path) as f:
config = json.load(f)
poppy = from_vrep(config=config, vrep_host='127.0.0.1', vrep_port=19997, vrep_scene='poppy-sitting.ttt')
It's important to note that the rest of the notebook will work exactly the same whether if you use the real robot or the simulated version.
This is very important is it will allow you to run the same code in both cases. For instance, you could use the simulator to debug your code before running it on the real robot. In our team, we also use it to run an compare the same experiment run in a simulation or in the real world.
The simulated version of the robot add the method reset_simulation which is a very convenient way to run the eact same experimentmultiple time. Unfortunately, you will have to do that with your own hands in the real world :-)
The next step is to start the synchronization between hardware motors/sensors to their software equivalent:
In [3]:
poppy.start_sync()
Now, all the motor registers should reflect their real values - actually the last retrieved one.
You have to note the sync frequency may vary from one sensor to another: e.g. the present_position is refreshed at 50Hz while the present_temperature only at 1Hz.
You can access the list of the motors connected to your robot using the motors property:
In [4]:
poppy.motors
Out[4]:
Or show only their names
In [5]:
[m.name for m in poppy.motors]
Out[5]:
You can also access motors individually directly by their names:
In [6]:
poppy.l_hip_y
Out[6]:
You can then access all register values:
In [7]:
poppy.l_hip_y.present_position
Out[7]:
In [8]:
poppy.l_hip_y.present_temperature
Out[8]:
Using list comprehension, you can easily retrieve the value of a register for each motors.
Retrieve a dictionary {motor_name: position}
just by doing:
In [9]:
{m.name: m.present_position for m in poppy.motors}
Out[9]:
Sending motor commands is really similar to reading them.
Let's try to make Poppy's head move a bit.
First, we have to make the motor uncompliant (dynamixel motors are set to compliant by default).
In [10]:
poppy.head_z.compliant = False
And then we can set a new goal_position:
In [11]:
poppy.head_z.goal_position = 10.
We can of course makes it move to a relative position using its current one:
In [12]:
poppy.head_z.goal_position = poppy.head_z.present_position + 10
Similarly you can make Poppy's head follows a sinusoid with the following line of codes:
We will use numpy to compute the sinus and matplotlib to plot it.
In [13]:
%pylab inline
amp = 30 # in degrees
freq = 0.3 # in Hz
duration = 10 # in s
# Our sinus will be send at 50Hz to match the refresh frequency.
# This is not at all mandatory, yet sending at a higher frequency will have no impact.
step = 1 / 50.
N = duration / step
t = linspace(0, duration, N)
pos = amp * sin(2 * pi * freq * t)
Let's plot it to make sure everything is fined.
In [14]:
plot(t, pos)
Out[14]:
And to apply it on the real robot:
In [15]:
import time
for p in pos:
poppy.head_z.goal_position = p
time.sleep(step)
You should now see your Poppy turns its head :-)
BTW, You could have done this in a much simpler way using primitives but that's another story...