Skip to content

Commit 62d365a

Browse files
authored
Merge pull request #220 from NOSALRO/robot_examples
Updated Supported Robots
2 parents 011000c + 68ff90c commit 62d365a

File tree

13 files changed

+233
-18
lines changed

13 files changed

+233
-18
lines changed

docs/images/tiago.png

104 KB
Loading

docs/images/vx300.png

17.8 KB
Loading

docs/robots/index.html

+104-14
Large diffs are not rendered by default.

docs/search/search_index.json

+1-1
Large diffs are not rendered by default.

docs/sitemap.xml.gz

0 Bytes
Binary file not shown.

src/docs/docs/images/tiago.png

104 KB
Loading

src/docs/docs/images/vx300.png

17.8 KB
Loading

src/docs/docs/robots.md

+38-2
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ We have two URDF files:
4949
{{TALOS}}
5050
=== "Python"
5151
{{TALOS_PYTHON}}
52-
52+
5353
- `utheque/talos/talos_fast.urdf`:
5454
* no collision except for the feet, which are approximated by boxes
5555
* grippers are fixed (no movement is allowed)
@@ -197,6 +197,43 @@ This hexapod is a simple 6-legged robot based on dynamixel actuators. It is simi
197197
=== "Python"
198198
{{HELLO_WORLD_ROBOT_CREATION_PYTHON}}
199199

200+
## Vx-300
201+
![Vx-300 robotic arm](images/vx300.png){: style="display: block;margin-left: auto;margin-right: auto;width:70%"}
202+
203+
The ViperX-300 is a versatile robotic arm developed by [Interbotix](https://docs.trossenrobotics.com/interbotix_xsarms_docs/specifications/vx300.html). It is designed for a range of applications including education, research, and light industrial tasks.
204+
205+
- 5 degrees of freedom plus a gripper
206+
- URDF: [[vx300.urdf](https://github.com/NOSALRO/robot_dart/blob/master/utheque/vx300/vx300.urdf)]
207+
- Example: [[vx300.cpp](https://github.com/resibots/robot_dart/blob/master/src/examples/vx300.cpp)] [[vx300.py](https://github.com/resibots/robot_dart/blob/master/src/examples/python/vx300.py)]
208+
209+
!!! note "Load Vx-300"
210+
=== "C++"
211+
{{VX300}}
212+
=== "Python"
213+
{{VX300_PYTHON}}
214+
215+
216+
217+
## Tiago (PAL Robotics)
218+
![Tiago single-arm robot](images/tiago.png){: style="display: block;margin-left: auto;margin-right: auto;width:70%"}
219+
220+
Tiago is a mobile manipulator robot developed by [PAL Robotics](https://pal-robotics.com/robots/tiago/), designed for tasks such as navigation, object manipulation, and human-robot interaction.
221+
222+
- Datasheet: [pdf](https://pal-robotics.com/wp-content/uploads/2024/04/Datasheet-TIAGo.pdfs)
223+
- Height: 110 - 145 cm
224+
- Weight: 70 kg
225+
- Degrees of Freedom (DoF): 7 (Arm), 2 (Head), 2 (Mobile Base)
226+
- Force/Torque sensor in the gripper
227+
- URDF: [[tiago.urdf](https://github.com/NOSALRO/robot_dart/blob/master/utheque/tiago/tiago_steel.urdf)]
228+
- Example: [[tiago.cpp](https://github.com/resibots/robot_dart/blob/master/src/examples/tiago.cpp)] [[tiago.py](https://github.com/resibots/robot_dart/blob/master/src/examples/python/tiago.py)]
229+
230+
!!! note "Load Tiago"
231+
=== "C++"
232+
{{TIAGO}}
233+
=== "Python"
234+
{{TIAGO_PYTHON}}
235+
236+
200237
## Simple arm
201238
![simple arm robot](images/arm.png){: style="display: block;margin-left: auto;margin-right: auto;width:70%"}
202239

@@ -236,4 +273,3 @@ RobotDART gives you the ability to load custom robots that are defined in [URDF
236273
your_robot = robot_dart.Robot("path/to/model.urdf", your_model_packages)
237274
```
238275

239-

src/docs/include/macros.py

+1-1
Large diffs are not rendered by default.

src/examples/python/tiago.py

+57
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,57 @@
1+
import RobotDART as rd
2+
import time
3+
import numpy as np
4+
dt = 0.001
5+
simu = rd.RobotDARTSimu(dt)
6+
7+
# this is important for wheel collision; with FCL it does not work well
8+
simu.set_collision_detector("bullet")
9+
10+
freq = int(1//dt)
11+
# @TIAGO_PYTHON@
12+
robot = rd.Tiago(freq)
13+
# @TIAGO_PYTHON_END@
14+
print("the model used is [", robot.model_filename(), "]")
15+
16+
configuration = rd.gui.GraphicsConfiguration()
17+
configuration.width = 1280
18+
configuration.height = 960
19+
configuration.bg_color = [1.0, 1.0, 1.0, 1.0]
20+
graphics = rd.gui.Graphics(configuration)
21+
simu.set_graphics(graphics)
22+
graphics.look_at([0., 3., 2.], [0., 0., 0.25])
23+
graphics.record_video("tiago_dancing.mp4")
24+
25+
simu.add_checkerboard_floor()
26+
simu.add_robot(robot)
27+
28+
simu.set_control_freq(freq)
29+
wheel_dofs = ["wheel_right_joint", "wheel_left_joint"]
30+
arm_dofs = ["arm_1_joint",
31+
"arm_2_joint",
32+
"arm_3_joint",
33+
"arm_4_joint",
34+
"arm_5_joint",
35+
"torso_lift_joint"]
36+
37+
init_positions = robot.positions(arm_dofs)
38+
start = time.time()
39+
40+
while (simu.scheduler().next_time() < 20. and not simu.graphics().done()):
41+
if (simu.schedule(simu.control_freq())):
42+
delta_pos = [np.sin(simu.scheduler().current_time() * 2) + np.pi/2,
43+
np.sin(simu.scheduler().current_time() * 2),
44+
np.sin(simu.scheduler().current_time() * 2),
45+
np.sin(simu.scheduler().current_time() * 2),
46+
np.sin(simu.scheduler().current_time() * 2),
47+
np.sin(simu.scheduler().current_time() * 2)]
48+
commands = (init_positions + delta_pos) - robot.positions(arm_dofs)
49+
robot.set_commands(commands, arm_dofs)
50+
cmd = [0, 5]
51+
robot.set_commands(cmd, wheel_dofs)
52+
simu.step_world()
53+
54+
end = time.time()
55+
elapsed_seconds = end - start
56+
print("benchmark time: ", elapsed_seconds, " s")
57+
robot.reset()

src/examples/python/vx300.py

+28
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,28 @@
1+
import RobotDART as rd
2+
3+
# @VX300_PYTHON@
4+
robot = rd.Vx300()
5+
# @VX300_PYTHON_END@
6+
robot.set_actuator_types("servo")
7+
8+
ctrl = [0.0, 1.0, -1.5, 1.0, 0.5, 0.]
9+
10+
controller = rd.PDControl(ctrl)
11+
robot.add_controller(controller)
12+
13+
simu = rd.RobotDARTSimu()
14+
simu.set_collision_detector("fcl")
15+
16+
simu.set_graphics(rd.gui.Graphics())
17+
simu.add_robot(robot)
18+
simu.add_checkerboard_floor()
19+
20+
for n in robot.dof_names():
21+
print(n)
22+
23+
simu.run(2.5)
24+
25+
ctrl = [0.0, -0.5, 0.5, -0.5, 0., 1.]
26+
controller.set_parameters(ctrl)
27+
controller.set_pd(20., 0.)
28+
simu.run(2.5)

src/examples/tiago.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,9 @@ int main()
1313
simu.set_collision_detector("bullet");
1414

1515
size_t freq = 1. / dt;
16+
// @TIAGO@
1617
auto robot = std::make_shared<robot_dart::robots::Tiago>(freq);
18+
// @TIAGO_END@
1719
std::cout << "The model used is: [" << robot->model_filename() << "]" << std::endl;
1820

1921
#ifdef GRAPHIC

src/examples/vx300.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,9 @@
88

99
int main()
1010
{
11+
// @VX300@
1112
auto robot = std::make_shared<robot_dart::robots::Vx300>();
13+
// @VX300_END@
1214
robot->set_actuator_types("servo");
1315

1416
Eigen::VectorXd ctrl = robot_dart::make_vector({0.0, 1.0, -1.5, 1.0, 0.5, 0.});

0 commit comments

Comments
 (0)