add test examples
This commit is contained in:
parent
a8a9fc0e5e
commit
6ca5bbe646
5 changed files with 92 additions and 0 deletions
|
@ -32,6 +32,8 @@ class MoveToPoseCartesianSkill(Node):
|
||||||
val = prop["value"]
|
val = prop["value"]
|
||||||
if nam == "server_name":
|
if nam == "server_name":
|
||||||
self.server_name = val
|
self.server_name = val
|
||||||
|
elif nam == "duration":
|
||||||
|
self.duration = float(val)
|
||||||
elif nam == "end_effector_velocity":
|
elif nam == "end_effector_velocity":
|
||||||
self.end_effector_velocity = float(val)
|
self.end_effector_velocity = float(val)
|
||||||
elif nam == "end_effector_acceleration":
|
elif nam == "end_effector_acceleration":
|
||||||
|
@ -42,6 +44,7 @@ class MoveToPoseCartesianSkill(Node):
|
||||||
self._completion = False
|
self._completion = False
|
||||||
self.end_effector_velocity = 1.0
|
self.end_effector_velocity = 1.0
|
||||||
self.end_effector_acceleration = 1.0
|
self.end_effector_acceleration = 1.0
|
||||||
|
self.duration = 5.0
|
||||||
# for other nodes
|
# for other nodes
|
||||||
kwargs["allow_undeclared_parameters"] = True
|
kwargs["allow_undeclared_parameters"] = True
|
||||||
kwargs["automatically_declare_parameters_from_overrides"] = True
|
kwargs["automatically_declare_parameters_from_overrides"] = True
|
||||||
|
@ -126,6 +129,7 @@ class MoveToPoseCartesianSkill(Node):
|
||||||
goal_msg.target_pose.orientation.w = pose["orientation"]["w"]
|
goal_msg.target_pose.orientation.w = pose["orientation"]["w"]
|
||||||
|
|
||||||
goal_msg.robot_name = dep["robot_name"]
|
goal_msg.robot_name = dep["robot_name"]
|
||||||
|
goal_msg.duration = self.duration
|
||||||
goal_msg.end_effector_velocity = self.end_effector_velocity
|
goal_msg.end_effector_velocity = self.end_effector_velocity
|
||||||
goal_msg.end_effector_acceleration = self.end_effector_acceleration
|
goal_msg.end_effector_acceleration = self.end_effector_acceleration
|
||||||
return goal_msg
|
return goal_msg
|
||||||
|
|
32
test_examples/README.md
Normal file
32
test_examples/README.md
Normal file
|
@ -0,0 +1,32 @@
|
||||||
|
## Пример запуска симуляции (runtime) сцены с роботом
|
||||||
|
|
||||||
|
Запустить последовательно четыре терминала и выполнить запуск 3-х launch-файлов и симулятора Gazebo:
|
||||||
|
Во всех терминалах выполнить предварительную настройку:
|
||||||
|
```sh
|
||||||
|
# ROS2
|
||||||
|
source /opt/ros/humble/setup.bash
|
||||||
|
# Robossembler
|
||||||
|
cd ~/robossembler-ws
|
||||||
|
source install/setup.bash
|
||||||
|
```
|
||||||
|
|
||||||
|
* 1 - запуск интерфейсной ноды с серверами навыков
|
||||||
|
```bash
|
||||||
|
ros2 launch rbs_bt_executor interface.launch.py bt_path:=src/robossembler-ros2/test_examples/bt_default
|
||||||
|
```
|
||||||
|
* 2 - запуск runtime с роботом в сцене
|
||||||
|
```bash
|
||||||
|
ros2 launch rbs_bringup rbs_bringup.launch.py
|
||||||
|
```
|
||||||
|
* 3 - запуск Gazebo (для визуализации процесса)
|
||||||
|
```bash
|
||||||
|
ign gazebo -g
|
||||||
|
```
|
||||||
|
* 4 - запуск дерева поведения
|
||||||
|
```bash
|
||||||
|
ros2 launch rbs_bt_executor rbs_bt_web.launch.py bt_path:=src/robossembler-ros2/test_examples/bt_default
|
||||||
|
```
|
||||||
|
Чтобы наблюдать сцену с движением робота, нужно перейти в окно Gazebo.
|
||||||
|
|
||||||
|

|
||||||
|
*визуализация сцены с роботом*
|
7
test_examples/bt_default/bt.xml
Normal file
7
test_examples/bt_default/bt.xml
Normal file
|
@ -0,0 +1,7 @@
|
||||||
|
<root BTCPP_format="4">
|
||||||
|
<BehaviorTree ID="Main">
|
||||||
|
<Sequence>
|
||||||
|
<Action ID="RbsAction" do="MoveToPose" command="move" sid="a"></Action>
|
||||||
|
</Sequence>
|
||||||
|
</BehaviorTree>
|
||||||
|
</root>
|
49
test_examples/bt_default/skills.json
Normal file
49
test_examples/bt_default/skills.json
Normal file
|
@ -0,0 +1,49 @@
|
||||||
|
{
|
||||||
|
"skills": [
|
||||||
|
{
|
||||||
|
"sid": "a",
|
||||||
|
"SkillPackage": { "name": "Robossembler", "version": "1.0", "format": "1" },
|
||||||
|
"Module": { "node_name": "skill_mtp", "name": "MoveToPose", "description": "Move to Pose skill" },
|
||||||
|
"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.3, "y": -0.2, "z": 0.2}, "orientation": {"x":0.0, "y":1.0, "z":0.0, "w": 0.0} } }
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"typeAction": "ACTION"
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"topicsOut": [],
|
||||||
|
"Settings": {
|
||||||
|
"output": {
|
||||||
|
"params": [
|
||||||
|
{
|
||||||
|
"name": "server_name",
|
||||||
|
"value3": "mtp_jtc",
|
||||||
|
"value2": "mtp_moveit",
|
||||||
|
"value": "mtp_cart"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "duration",
|
||||||
|
"value": "5.0"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "end_effector_velocity",
|
||||||
|
"value": "1.0"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "end_effector_acceleration",
|
||||||
|
"value": "1.0"
|
||||||
|
}
|
||||||
|
]
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
]
|
||||||
|
}
|
BIN
test_examples/gazebo_rbs_arm.png
Normal file
BIN
test_examples/gazebo_rbs_arm.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 149 KiB |
Loading…
Add table
Add a link
Reference in a new issue