![]() |
---|
Example trajectory visualization |
See instructions to build or download the containerized iscoin_simulator
.
Depending on hardware availability, run the container with docker compose
and either the gpu
or cpu
argument
docker compose run --rm --name iscoin_simulator gpu|cpu
Inside the container, the UR3e simulator can be started from the terminal with
ros2 launch iscoin_simulation_gz iscoin_sim_control.launch.py
which will open the Gazebo Ignition display locally, on the host device. To send commands to the simulated robot, another terminal window is needed. This can be done by using a terminal multiplexer like tmux
or by entering the running container through another terminal with
docker exec -it iscoin_simulator /bin/bash
As an example, run the following command from the new terminal window to simulate a demo trajectory:
ros2 run iscoin_driver demo.py
The trajectories to be simulated are saved as json
in the iscoin_driver/config
directory. Custom trajectories can be passed to the demo script in the following manner:
ros2 run iscoin_driver demo.py --ros-args -p traj:=<path-to>/custom_traj.json
To quit the simulator, close the window or use CTRL+C
in the corresponding terminal.
The inverse kinematics library is based on ur_ikfast which has been extended to support the iscoin
robot (i.e., UR3e + Hand-e). The library can be invoked directly from Python code in the docker environment.
from ur_ikfast import ur_kinematics
iscoin_arm = ur_kinematics.URKinematics('iscoin')
joint_angles = [-3.1, -1.6, 1.6, -1.6, -1.6, 0.] # in radians
print("joint angles", joint_angles)
pose_quat = iscoin_arm.forward(joint_angles)
pose_matrix = iscoin_arm.forward(joint_angles, 'matrix')
print("forward() quaternion \n", pose_quat)
print("forward() matrix \n", pose_matrix)
# print("inverse() all", iscoin_arm.inverse(pose_quat, True))
print("inverse() one from quat", iscoin_arm.inverse(pose_quat, False, q_guess=joint_angles))
print("inverse() one from matrix", iscoin_arm.inverse(pose_matrix, False, q_guess=joint_angles))