\(q_{k} = q_{k-1} + \dot{q}*\delta t\)
And the function is equivalent to pressing 2
key when control by keyboard.
③ armCtrlInCartesian()
In cartesian space, the user was originally required to control the sptial velocity \(V = [\omega \quad v]'\), that is, unitreeArm.twist
to control the robot, and the function was encapsulated on this basis. Then the user can directly control the direction in which the end of the robot was desired.
The following command calculation will be performed directly in the function:
where T is a homogeneous transformation matrix composed of R and p, and [ω] is the antisymmetric matrix of ω.
\(posture_k = posture_{k-1}+posture_{\Delta}\)
\(T_k = T_{\Delta} + T_{k-1}\)
\([\omega] = \log{(R_{k-1}^T R_k)}\)
\(v=p_\Delta\)
And the function is equivalent to pressing 3
key when control by keyboard.
If user wants to control the robot through the planning trajectory, they can view this example.
When sendRecvThread->start()
executes, the thread executes arm.sendRecv()
at a frequency of 500HZ.
When controlling under the joint space, this function will send q, qd, gripperQ, gripperW
in unitreeArm to the z1_controller, When controlling under the cartesian space, the function will send twist
in unitreeArm to the z1_controller, and the user only needs to keep changing these parameters to control the robotic arm. You can also write your own thread to call unitreeArm.sendRecv().
If the user wants to control the \(q, \dot{q}, \tau_f, k_p, k_d\) parameters of the motor directly, they can view this example.
This file shows how to send PD parameters directly to the motor. Users can control the motor by writing their own program to achieve independment development. The final output torque of the motor is as follows:
\[\tau = k_p * 25.6 * (q_d - q) + k_d * 0.0128 * (\dot{q_d} - \dot{q}) + \tau_f\]25.6 and 0.0128 are the scaling multiples in the communication protocol with the motor.
The sendRecvThread
under CtrlComponents
is a function that calls unitreeArm
for instruction operations, such as running to forward as an instruction
And when running lowcmd, it is recommended to use its own defined thread, execute the run
function, the run function starts to determine the command that needs to be sent to the motor through calculation, and finally calls sendRecv to send UDP packets.
This program provides example of controlling munltiple robotic arms.
For more information, see SDK run
This contains the Python version interface of the z1 SDK.
The interface is designed in the arm_python_interface.cpp
file, and the functions and variables already included in it can be used directly in Python, and users can also change them by themselves, see for details pybind11 documentation
invoke method:
There will be a library named unitree_arm_interface
in z1_sdk/lib
after compilation is complete.
Execute ./z1_ctrl
in the first terminal.
Open a second terminal in the z1_sdk/examples_py
directory to execute python3 example_highcmd.py