reachy_sdk.head
¶
Reachy Head module.
Handles all specific method to an Head: - the inverse kinematics - look_at function
- class reachy_sdk.head.Head(joints, grpc_channel)¶
Head class.
It exposes the neck orbita actuator at the base of the head. It provides look_at utility function to directly orient the head so it looks at a cartesian point expressed in Reachy’s coordinate system.
- look_at(x, y, z, duration, starting_positions=None, sampling_freq=100, interpolation_mode=<function linear>)¶
Compute and send disks position to look at the (x, y, z) point in Reachy cartesian space.
X is forward, Y is left and Z is upward. They all expressed in meters.
This function will block until the movement is over. See look_at_async for an asynchronous version.
- async look_at_async(x, y, z, duration, starting_positions=None, sampling_freq=100, interpolation_mode=<function linear>)¶
Compute and send disks position to look at the (x, y, z) point in Reachy cartesian space.
X is forward, Y is left and Z is upward. They all expressed in meters.
This function is asynchronous and will return a Coroutine. This can be used to easily combined multiple goto/look_at. See look_at for an blocking version.
- property neck_orbita_joints¶
Get the 3 joints composing the Orbita neck.