Skip to content

Commit

Permalink
feat: rai_bench (#436)
Browse files Browse the repository at this point in the history
Co-authored-by: Maciej Majek <[email protected]>
Co-authored-by: Bartłomiej Boczek <[email protected]>
Co-authored-by: MagdalenaKotynia <[email protected]>

chore: pre-commit
  • Loading branch information
jmatejcz authored and maciejmajek committed Feb 26, 2025
1 parent ff0585e commit 3dc3d15
Show file tree
Hide file tree
Showing 30 changed files with 1,229 additions and 165 deletions.
2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -172,3 +172,5 @@ logs/

src/examples/*-demo
artifact_database.pkl

imgui.ini
49 changes: 5 additions & 44 deletions examples/manipulation-demo.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,22 +12,16 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import rclpy
from launch import LaunchContext, LaunchDescription
from launch import LaunchDescription
from launch.actions import (
DeclareLaunchArgument,
ExecuteProcess,
IncludeLaunchDescription,
OpaqueFunction,
RegisterEventHandler,
)
from launch.event_handlers import OnExecutionComplete, OnProcessStart
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from rclpy.qos import QoSProfile, ReliabilityPolicy
from rosgraph_msgs.msg import Clock


def generate_launch_description():
Expand All @@ -46,21 +40,6 @@ def generate_launch_description():
output="screen",
)

def wait_for_clock_message(context: LaunchContext, *args, **kwargs):
rclpy.init()
node = rclpy.create_node("wait_for_game_launcher")
node.create_subscription(
Clock,
"/clock",
lambda msg: rclpy.shutdown(),
QoSProfile(depth=1, reliability=ReliabilityPolicy.BEST_EFFORT),
)
rclpy.spin(node)
return None

# Game launcher will start publishing the clock message after loading the simulation
wait_for_game_launcher = OpaqueFunction(function=wait_for_clock_message)

launch_moveit = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[
Expand All @@ -72,7 +51,7 @@ def wait_for_clock_message(context: LaunchContext, *args, **kwargs):
launch_robotic_manipulation = Node(
package="robotic_manipulation",
executable="robotic_manipulation",
name="robotic_manipulation_node",
# name="robotic_manipulation_node",
output="screen",
parameters=[
{"use_sim_time": True},
Expand All @@ -90,28 +69,10 @@ def wait_for_clock_message(context: LaunchContext, *args, **kwargs):

return LaunchDescription(
[
# Include the game_launcher argument
game_launcher_arg,
# Launch the game launcher and wait for it to load
launch_game_launcher,
RegisterEventHandler(
event_handler=OnProcessStart(
target_action=launch_game_launcher,
on_start=[
wait_for_game_launcher,
],
)
),
# Launch the MoveIt node after loading the simulation
RegisterEventHandler(
event_handler=OnExecutionComplete(
target_action=wait_for_game_launcher,
on_completion=[
launch_openset,
launch_moveit,
launch_robotic_manipulation,
],
)
),
launch_openset,
launch_moveit,
launch_robotic_manipulation,
]
)
20 changes: 10 additions & 10 deletions examples/manipulation-demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,37 +12,37 @@
# See the License for the specific language goveself.rning permissions and
# limitations under the License.

import threading

import rclpy
import rclpy.qos
from langchain_core.messages import HumanMessage
from rai.agents.conversational_agent import create_conversational_agent
from rai.node import RaiBaseNode
from rai.communication.ros2.connectors import ROS2ARIConnector
from rai.tools.ros.manipulation import GetObjectPositionsTool, MoveToPointTool
from rai.tools.ros.native import GetCameraImage, Ros2GetTopicsNamesAndTypesTool
from rai.tools.ros2.topics import GetROS2ImageTool, GetROS2TopicsNamesAndTypesTool
from rai.utils.model_initialization import get_llm_model
from rai_open_set_vision.tools import GetGrabbingPointTool


def create_agent():
rclpy.init()
node = RaiBaseNode(node_name="manipulation_demo")
connector = ROS2ARIConnector()
node = connector.node
node.declare_parameter("conversion_ratio", 1.0)

threading.Thread(target=node.spin).start()

tools = [
GetObjectPositionsTool(
node=node,
connector=connector,
target_frame="panda_link0",
source_frame="RGBDCamera5",
camera_topic="/color_image5",
depth_topic="/depth_image5",
camera_info_topic="/color_camera_info5",
get_grabbing_point_tool=GetGrabbingPointTool(connector=connector),
),
MoveToPointTool(node=node, manipulator_frame="panda_link0"),
GetCameraImage(node=node),
Ros2GetTopicsNamesAndTypesTool(node=node),
MoveToPointTool(connector=connector, manipulator_frame="panda_link0"),
GetROS2ImageTool(connector=connector),
GetROS2TopicsNamesAndTypesTool(connector=connector),
]

llm = get_llm_model(model_type="complex_model", streaming=True)
Expand Down
15 changes: 14 additions & 1 deletion poetry.lock

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

3 changes: 2 additions & 1 deletion pyproject.toml
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ rai = {path = "src/rai_core", develop = true}
rai_asr = {path = "src/rai_asr", develop = true}
rai_tts = {path = "src/rai_tts", develop = true}
rai_sim = {path = "src/rai_sim", develop = true}
rai_bench = {path = "src/rai_bench", develop = true}

langchain-core = "^0.3"
langchain = "*"
Expand All @@ -30,7 +31,6 @@ requests = "^2.32.2"
pre-commit = "^3.7.0"
openai = "^1.23.3"
coloredlogs = "^15.0.1"
opencv-python = "^4.9.0.80"
markdown = "^3.6"
boto3 = "^1.34.98"
tqdm = "^4.66.4"
Expand Down Expand Up @@ -62,6 +62,7 @@ pytest-timeout = "^2.3.1"
tomli-w = "^1.1.0"
faster-whisper = "^1.1.1"
pydub = "^0.25.1"
opencv-python = "^4.11.0.86"
[tool.poetry.group.dev.dependencies]
ipykernel = "^6.29.4"

Expand Down
3 changes: 3 additions & 0 deletions setup_shell.sh
Original file line number Diff line number Diff line change
Expand Up @@ -30,3 +30,6 @@ esac

export PYTHONPATH
PYTHONPATH="$(dirname "$(dirname "$(poetry run which python)")")/lib/python$(poetry run python --version | awk '{print $2}' | cut -d. -f1,2)/site-packages:$PYTHONPATH"
PYTHONPATH="src/rai_core:$PYTHONPATH"
PYTHONPATH="src/rai_asr:$PYTHONPATH"
PYTHONPATH="src/rai_tts:$PYTHONPATH"
60 changes: 60 additions & 0 deletions src/rai_bench/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
## RAI Benchmark

## Description

The RAI Bench is a package including benchmarks and providing frame for creating new benchmarks

## Frame Components

Frame components can be found in `src/rai_bench/rai_bench/benchmark_model.py`

- `Task` - abstract class for creating specific task. It introduces helper funtions that make it easier to calculate metrics/scores. Your custom tasks must implement a prompt got agent to do, a way to calculate a result and a validation if given scene config suits the task.
-
- `Scenario` - class defined by a Scene and Task. Can be created manually like:

```python

```

- `Benchmark` - class responsible for running and logging scenarios.

### O3DE TEST BENCHMARK

O3DE Test Benchmark (src/rai_bench/rai_bench/o3de_test_bench/), contains 2 Tasks(tasks/) - GrabCarrotTask and PlaceCubesTask (these tasks implement calculating scores) and 4 scene_configs(configs/) for O3DE robotic arm simulation.

Both tasks calculate score, taking into consideration 4 values:

- initially_misplaced_now_correct - when the object which was in the incorrect place at the start, is in a correct place at the end
- initially_misplaced_still_incorrect - when the object which was in the incorrect place at the start, is in a incorrect place at the end
- initially_correct_still_correct - when the object which was in the correct place at the start, is in a correct place at the end
- initially_correct_now_incorrect - when the object which was in the correct place at the start, is in a incorrect place at the end

The result is a value between 0 and 1, calculated like (initially_misplaced_now_correct + initially_correct_still_correct) / number_of_initial_objects.
This score is calculated at the beggining and at the end of each scenario.

### Example usage

Example of how to load scenes, define scenarios and run benchmark can be found in `src/rai_bench/rai_bench/benchmark_main.py`

Scenarios can be loaded manually like:

```python
one_carrot_simulation_config = O3DExROS2SimulationConfig.load_config(
base_config_path=Path("path_to_scene.yaml"),
connector_config_path=Path("path_to_o3de_config.yaml"),
)

Scenario(task=GrabCarrotTask(logger=some_logger), simulation_config=one_carrot_simulation_config)
```

or automatically like:

```python
scenarios = Benchmark.create_scenarios(
tasks=tasks, simulation_configs=simulations_configs
)
```

which will result in list of scenarios with combination of every possible task and scene(task decides if scene config is suitable for it).

Both approaches can be found in `main.py`
17 changes: 17 additions & 0 deletions src/rai_bench/pyproject.toml
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
[tool.poetry]
name = "rai-bench"
version = "0.1.0"
description = ""
authors = ["jmatejcz <[email protected]>"]
readme = "README.md"

packages = [
{ include = "rai_bench", from = "." },
]
[tool.poetry.dependencies]
python = "^3.10"


[build-system]
requires = ["poetry-core"]
build-backend = "poetry.core.masonry.api"
Loading

0 comments on commit 3dc3d15

Please sign in to comment.