API Reference#
fourier_grx_client.client.RobotClient
#
Bases: ZenohSession
Client class for GR series robots. Example:
1 2 | |
base_pose
property
#
Get the current base pose.
base_velocity
property
#
Get the current base velocity.
imu_angles
property
#
Get the current IMU orientation as Euler angles.
imu_angular_velocity
property
#
Get the current IMU angular velocity.
imu_linear_acceleration
property
#
Get the current IMU linear acceleration.
imu_quaternion
property
#
Get the current IMU orientation as a quaternion.
is_moving
property
writable
#
Whether the robot is currently moving.
joint_currents
property
#
Get the current joint currents of the robot.
joint_efforts
property
#
Get the current joint efforts of the robot.
joint_positions
property
#
Get the current joint positions of the robot. The joint positions are in radians.
joint_velocities
property
#
Get the current joint velocities of the robot. The joint velocities are in radians per second.
__init__(freq=400, namespace=None, server_ip='localhost', verbose=False)
#
The client class for GR series robots.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
server_ip |
str
|
IP address of the grx server. Please make sure to properly setup the firewall to allow port 7447. Defaults to "localhost". |
'localhost'
|
freq |
int
|
Robot state update frequency. Usually the user doesn't need to modify this. Defaults to 400. |
400
|
namespace |
str
|
Robot namespace. If not provided, it will try to use the |
None
|
Raises:
| Type | Description |
|---|---|
FourierConnectionError
|
If the connection to the server failed. |
calibrate_sensors()
#
Get sensor offsets and save to sensor_offset.json
control_joints(control_type, commands, degrees=False)
#
Control the joints in a group with the specified control type.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
control_type |
Literal['position', 'velocity', 'current']
|
The control type to set. |
required |
commands |
ndarray | list
|
The control commands to set. |
required |
degrees |
bool
|
Whether the joint positions and velocities are in degrees. Defaults to False. |
False
|
disable()
#
Disable the motors.
enable()
#
Enable the motors.
forward_kinematics(chain_names, q=None)
#
Get the end effector pose of the specified chains in base_link frame.
Info
The available chain names are: head, left_arm, right_arm, with corresponding end effector frames: head_yaw_link, left_end_effector_link, right_end_effector_link, and the transformation matrices are in the base_link frame.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
chain_names |
list[str]
|
The chains to get the end effector pose of. Available chain names: 'head', 'left_arm', 'right_arm'. |
required |
q |
ndarray
|
The robot confiuration to do forward kinematics in. Defaults to None. |
None
|
Returns:
| Name | Type | Description |
|---|---|---|
list |
list[ndarray]
|
The end effector pose is a list of 4x4 transformation matrices. The order of the matrices is the same as the order of the chain names. The transformation matrix is in the |
get_control_modes()
#
Get the control modes for all joints.
get_gains()
#
Get the control gains for all joints.
get_group_current(group)
#
Get the joint currents of a group.
get_group_effort(group)
#
Get the joint efforts of a group.
get_group_position(group)
#
Get the joint positions of a group.
get_group_position_by_name(name)
#
Get the joint positions of a group by its name.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
name |
str
|
The name of the group. Available group names: 'left_leg', 'right_leg', 'waist', 'head', 'left_arm', 'right_arm'. |
required |
get_group_velocity(group)
#
Get the joint velocities of a group.
get_transform(target_frame, source_frame, q=None)
#
Get the transformation matrix between two frames in configuration q. If q is None, the current joint positions are used.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
target_frame |
str
|
Name of the frame to get the pose of. |
required |
source_frame |
str
|
Name of the frame to get the pose in. |
required |
q |
ndarray
|
The robot confiuration to do forward kinematics in. Defaults to None. |
None
|
Returns:
| Type | Description |
|---|---|
|
np.ndarray: The transformation matrix. |
inverse_kinematics(chain_names, targets, move=False, dt=0.005, velocity_scaling_factor=1.0, convergence_threshold=1e-08)
#
Get the joint positions for the specified chains to reach the target pose in base_link frame.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
chain_names |
list[str]
|
The chains to get the joint positions for. Available chain names: 'head', 'left_arm', 'right_arm'. |
required |
targets |
list[ndarray]
|
The target poses in base_link frame. |
required |
move |
bool
|
Whether to move the robot to the target pose. Defaults to False. |
False
|
dt |
float
|
The time step for the inverse kinematics. |
0.005
|
Returns:
| Type | Description |
|---|---|
ndarray
|
np.ndarray: The joint positions to reach the target pose (in radians). |
list_frames()
#
List all available frames.
liveness_check(timeout=1.0)
#
Check if the robot server is alive.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
timeout |
float
|
Timeout in seconds. Defaults to 1.0. |
1.0
|
Raises:
| Type | Description |
|---|---|
FourierConnectionError
|
If the connection to the server failed. |
move_joints(group, positions, duration=0.0, degrees=False, blocking=True, gravity_compensation=False)
#
Move in joint space with time duration.
Move in joint space with time duration in a separate thread. Can be aborted using abort(). Can be blocking.
If the duration is set to 0, the joints will move in their maximum speed without interpolation.
GR1T2 Joint Order
The joints order is as follows: 0: left_hip_roll_joint 1: left_hip_yaw_joint 2: left_hip_pitch_joint 3: left_knee_pitch_joint 4: left_ankle_pitch_joint 5: left_ankle_roll_joint 6: right_hip_roll_joint 7: right_hip_yaw_joint 8: right_hip_pitch_joint 9: right_knee_pitch_joint 10: right_ankle_pitch_joint 11: right_ankle_roll_joint 12: waist_yaw_joint 13: waist_pitch_joint 14: waist_roll_joint 15: head_pitch_joint 16: head_roll_joint 17: head_yaw_joint 18: left_shoulder_pitch_joint 19: left_shoulder_roll_joint 20: left_shoulder_yaw_joint 21: left_elbow_pitch_joint 22: left_wrist_yaw_joint 23: left_wrist_roll_joint 24: left_wrist_pitch_joint 25: right_shoulder_pitch_joint 26: right_shoulder_roll_joint 27: right_shoulder_yaw_joint 28: right_elbow_pitch_joint 29: right_wrist_yaw_joint 30: right_wrist_roll_joint 31: right_wrist_pitch_joint
Example:
1 2 3 4 5 6 7 8 | |
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
group |
ControlGroup | list | str
|
The group of joints to move, specified by a string or a ControlGroup enum, or a list of joint indices. |
required |
positions |
ndarray[float]
|
target joint position in degrees. |
required |
duration |
float
|
Time duration in seconds. If set to 0, the joints will move in their maximum speed without interpolation. Defaults to 0.0. |
0.0
|
degrees |
bool
|
Whether the joint positions are in degrees. Defaults to False. |
False
|
blocking |
bool
|
If True, block until the move is completed. Defaults to True. |
True
|
gravity_compensation |
bool
|
Whether to enable gravity compensation. Defaults to False. |
False
|
movej(sides, target_positions, target_velocity=None, target_acceleration=None, max_velocity=None, max_acceleration=None, max_jerk=None, degrees=False, move=True)
#
move the joints of the arms to the target position.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
sides |
list[Literal['left', 'right']]
|
Sides of the arms to move. Can be "left" or "right". |
required |
target_positions |
list[ndarray | list]
|
Desired joint positions. |
required |
target_velocity |
list[ndarray | list] | None
|
Desired joint velocities. Defaults to None. If None, the robot will estimate the velocity based on the target position. |
None
|
target_acceleration |
list[ndarray | list] | None
|
Desired accelerations. Defaults to None. |
None
|
max_velocity |
list[ndarray | list] | None
|
Max velocity during trajectory generation. Defaults to None. If None, the robot will use the default max velocity at 5 rad/s. |
None
|
max_acceleration |
list[ndarray | list] | None
|
Max acceleration during trajectory generation. Defaults to None. If None, the robot will use the default max acceleration at 10 rad/s^2. |
None
|
max_jerk |
list[ndarray | list] | None
|
Max jerk during trajectory generation. Defaults to None. If None, the robot will use the default max jerk at 50 rad/s^3. |
None
|
degrees |
bool
|
True if the input is in degrees. Defaults to False. |
False
|
move |
bool
|
Whether to execute the trajectory. Defaults to True. |
True
|
Returns:
| Name | Type | Description |
|---|---|---|
list |
list[list[ndarray]]
|
The trajectory of joint positions and velocities for controlled arms to reach the target pose. |
movel(sides, target_poses, max_velocity=None, max_acceleration=None, max_jerk=None, move=True)
#
Move the specified arm to the target position.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
sides |
list[Literal['left', 'right']]
|
Sides of the arms to move. Can be "left" or "right". |
required |
target_poses |
list[ndarray]
|
Desired end effector poses. |
required |
max_velocity |
float | None
|
Max velocity during trajectory generation. Defaults to None. |
None
|
max_acceleration |
float | None
|
Max acceleration during trajectory generation. Defaults to None. |
None
|
max_jerk |
float | None
|
Max jerk during trajectory generation. Defaults to None. |
None
|
move |
bool
|
Whether to execute the trajectory. Defaults to True. |
True
|
Return
list: The trajectory to reach the target pose.
play_traj(group, traj, timestamps=None, dt=0.005)
#
Play a trajectory in joint space.
reboot()
#
Reboot the motors.
set_control_modes(control_mode=None)
#
Set the control modes for all joints.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
control_mode |
ControlMode | list[ControlMode] | None
|
ControlMode can be PD, VELOCITY, CURRENT. Defaults to None. |
None
|
set_enable(enable)
#
Enable or disable the motors.
fourier_grx_client.utils.ControlGroup
#
Bases: tuple, Enum
Control group enumeration. Each group is a tuple of (start, num_joints). Available groups are: ALL, LEFT_LEG, RIGHT_LEG, WAIST, HEAD, LEFT_ARM, RIGHT_ARM, LOWER, UPPER, UPPER_EXTENDED.
Source code in src/fourier_grx_client/utils.py
47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 | |
fourier_grx_client.utils.ControlMode
#
Bases: IntEnum
Control mode enumeration.
Source code in src/fourier_grx_client/utils.py
35 36 37 38 39 40 41 42 43 44 | |