add mode "benchmark"
This commit is contained in:
parent
6ca5bbe646
commit
ba4e51d06f
7 changed files with 222 additions and 9 deletions
|
@ -11,22 +11,56 @@ source install/setup.bash
|
|||
```
|
||||
|
||||
* 1 - запуск интерфейсной ноды с серверами навыков
|
||||
```bash
|
||||
```sh
|
||||
ros2 launch rbs_bt_executor interface.launch.py bt_path:=src/robossembler-ros2/test_examples/bt_default
|
||||
```
|
||||
* 2 - запуск runtime с роботом в сцене
|
||||
```bash
|
||||
```sh
|
||||
ros2 launch rbs_bringup rbs_bringup.launch.py
|
||||
```
|
||||
* 3 - запуск Gazebo (для визуализации процесса)
|
||||
```bash
|
||||
```sh
|
||||
ign gazebo -g
|
||||
```
|
||||
* 4 - запуск дерева поведения
|
||||
```bash
|
||||
```sh
|
||||
ros2 launch rbs_bt_executor rbs_bt_web.launch.py bt_path:=src/robossembler-ros2/test_examples/bt_default
|
||||
```
|
||||
Чтобы наблюдать сцену с движением робота, нужно перейти в окно Gazebo.
|
||||
|
||||

|
||||
*визуализация сцены с роботом*
|
||||
|
||||
## Пример запуска симуляции в режиме `benchmark` для оценки управления роботом через разные контроллеры
|
||||
|
||||
Запустить последовательно четыре терминала и выполнить запуск 3-х launch-файлов и симулятора Gazebo:
|
||||
Во всех терминалах выполнить предварительную настройку:
|
||||
```sh
|
||||
# ROS2
|
||||
source /opt/ros/humble/setup.bash
|
||||
# Robossembler
|
||||
cd ~/robossembler-ws
|
||||
source install/setup.bash
|
||||
```
|
||||
|
||||
* 1 - запуск интерфейсной ноды в режиме `benchmark`
|
||||
```sh
|
||||
ros2 launch rbs_bt_executor interface.launch.py bt_path:=src/robossembler-ros2/test_examples/bt_benchmark mode:=benchmark
|
||||
```
|
||||
* 2 - запуск runtime с роботом в сцене
|
||||
```sh
|
||||
ros2 launch rbs_bringup rbs_bringup.launch.py
|
||||
```
|
||||
* 3 - запуск Gazebo (для визуализации процесса)
|
||||
```sh
|
||||
ign gazebo -g
|
||||
```
|
||||
* 4 - запуск дерева поведения
|
||||
```sh
|
||||
ros2 launch rbs_bt_executor rbs_bt_web.launch.py bt_path:=src/robossembler-ros2/test_examples/bt_benchmark
|
||||
```
|
||||
|
||||
В терминале 1 (интерфейсная нода) будет отражаться время выполнения каждого действия:
|
||||
|
||||

|
||||
*пример вывода журнала*
|
||||
|
|
BIN
test_examples/benchmark_result.png
Normal file
BIN
test_examples/benchmark_result.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 157 KiB |
9
test_examples/bt_benchmark/bt.xml
Normal file
9
test_examples/bt_benchmark/bt.xml
Normal file
|
@ -0,0 +1,9 @@
|
|||
<root BTCPP_format="4">
|
||||
<BehaviorTree ID="Main">
|
||||
<Sequence>
|
||||
<Action ID="RbsAction" do="MoveToPose" command="move" sid="a"></Action>
|
||||
<Action ID="RbsAction" do="MoveToPose" command="move" sid="b"></Action>
|
||||
<Action ID="RbsAction" do="MoveToPose" command="move" sid="c"></Action>
|
||||
</Sequence>
|
||||
</BehaviorTree>
|
||||
</root>
|
135
test_examples/bt_benchmark/skills.json
Normal file
135
test_examples/bt_benchmark/skills.json
Normal file
|
@ -0,0 +1,135 @@
|
|||
{
|
||||
"skills": [
|
||||
{
|
||||
"sid": "a",
|
||||
"SkillPackage": { "name": "Robossembler", "version": "1.0", "format": "1" },
|
||||
"Module": { "node_name": "skill_mtp", "name": "MoveToPose", "description": "Move to the starting position" },
|
||||
"Launch": { "executable": "skill_movetopose.py", "package": "rbss_movetopose" },
|
||||
"BTAction": [
|
||||
{
|
||||
"name": "move",
|
||||
"type": "action",
|
||||
"param": [
|
||||
{
|
||||
"type": "move_to_pose",
|
||||
"dependency": { "robot_name": "rbs_arm",
|
||||
"pose": { "position": {"x":-0.45, "y":0.0, "z":0.3}, "orientation": {"x":0.0, "y":1.0, "z":0.0, "w": 0.0} } }
|
||||
}
|
||||
],
|
||||
"typeAction": "ACTION"
|
||||
}
|
||||
],
|
||||
"topicsOut": [],
|
||||
"Settings": {
|
||||
"output": {
|
||||
"params": [
|
||||
{
|
||||
"name": "server_name",
|
||||
"value": "mtp_jtc",
|
||||
"value2": "mtp_moveit",
|
||||
"value3": "mtp_cart"
|
||||
},
|
||||
{
|
||||
"name": "duration",
|
||||
"value": "5.0"
|
||||
},
|
||||
{
|
||||
"name": "end_effector_velocity",
|
||||
"value": "1.0"
|
||||
},
|
||||
{
|
||||
"name": "end_effector_acceleration",
|
||||
"value": "1.0"
|
||||
}
|
||||
]
|
||||
}
|
||||
}
|
||||
},
|
||||
{
|
||||
"sid": "b",
|
||||
"SkillPackage": { "name": "Robossembler", "version": "1.0", "format": "1" },
|
||||
"Module": { "node_name": "skill_mtp", "name": "MoveToPose", "description": "Move to pose with joint trajectory controller" },
|
||||
"Launch": { "executable": "skill_movetopose.py", "package": "rbss_movetopose" },
|
||||
"BTAction": [
|
||||
{
|
||||
"name": "move",
|
||||
"type": "action",
|
||||
"param": [
|
||||
{
|
||||
"type": "move_to_pose",
|
||||
"dependency": { "robot_name": "rbs_arm",
|
||||
"pose": { "position": {"x":-0.1, "y":-0.3, "z":0.3}, "orientation": {"x":0.0, "y":1.0, "z":0.0, "w": 0.0} } }
|
||||
}
|
||||
],
|
||||
"typeAction": "ACTION"
|
||||
}
|
||||
],
|
||||
"topicsOut": [],
|
||||
"Settings": {
|
||||
"output": {
|
||||
"params": [
|
||||
{
|
||||
"name": "server_name",
|
||||
"value": "mtp_jtc"
|
||||
},
|
||||
{
|
||||
"name": "duration",
|
||||
"value": "5.0"
|
||||
},
|
||||
{
|
||||
"name": "end_effector_velocity",
|
||||
"value": "1.0"
|
||||
},
|
||||
{
|
||||
"name": "end_effector_acceleration",
|
||||
"value": "1.0"
|
||||
}
|
||||
]
|
||||
}
|
||||
}
|
||||
},
|
||||
{
|
||||
"sid": "c",
|
||||
"SkillPackage": { "name": "Robossembler", "version": "1.0", "format": "1" },
|
||||
"Module": { "node_name": "skill_mtp", "name": "MoveToPose", "description": "Move to pose with cartesian controller" },
|
||||
"Launch": { "executable": "skill_movetopose.py", "package": "rbss_movetopose" },
|
||||
"BTAction": [
|
||||
{
|
||||
"name": "move",
|
||||
"type": "action",
|
||||
"param": [
|
||||
{
|
||||
"type": "move_to_pose",
|
||||
"dependency": { "robot_name": "rbs_arm",
|
||||
"pose": { "position": {"x":-0.45, "y":0.0, "z":0.3}, "orientation": {"x":0.0, "y":1.0, "z":0.0, "w": 0.0} } }
|
||||
}
|
||||
],
|
||||
"typeAction": "ACTION"
|
||||
}
|
||||
],
|
||||
"topicsOut": [],
|
||||
"Settings": {
|
||||
"output": {
|
||||
"params": [
|
||||
{
|
||||
"name": "server_name",
|
||||
"value": "mtp_cart"
|
||||
},
|
||||
{
|
||||
"name": "duration",
|
||||
"value": "5.0"
|
||||
},
|
||||
{
|
||||
"name": "end_effector_velocity",
|
||||
"value": "1.0"
|
||||
},
|
||||
{
|
||||
"name": "end_effector_acceleration",
|
||||
"value": "1.0"
|
||||
}
|
||||
]
|
||||
}
|
||||
}
|
||||
}
|
||||
]
|
||||
}
|
|
@ -13,7 +13,7 @@
|
|||
{
|
||||
"type": "move_to_pose",
|
||||
"dependency": { "robot_name": "rbs_arm",
|
||||
"pose": { "position": {"x": -0.3, "y": -0.2, "z": 0.2}, "orientation": {"x":0.0, "y":1.0, "z":0.0, "w": 0.0} } }
|
||||
"pose": { "position": {"x":-0.15, "y":-0.3, "z":0.3}, "orientation": {"x":0.0, "y":1.0, "z":0.0, "w": 0.0} } }
|
||||
}
|
||||
],
|
||||
"typeAction": "ACTION"
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue