Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
23 changes: 18 additions & 5 deletions .github/workflows/docker-build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -9,10 +9,23 @@ on:
jobs:
build:
runs-on: ubuntu-latest

steps:
- name: Checkout code
uses: actions/checkout@v3
- name: Checkout code
uses: actions/checkout@v3

- name: Build Docker image
run: |
docker build -t knowrob/ros1 .

- name: Build Docker image
run: docker build -t knowrob/ros1 .
- name: Run ROS unit tests
run: |
docker run --rm \
--entrypoint "" \
-v "${{ github.workspace }}:/catkin_ws/src/knowrob_ros:ro" \
-w /catkin_ws \
knowrob/ros1 bash -lc "\
source /opt/ros/noetic/setup.bash && \
catkin build knowrob_ros && \
source devel/setup.bash && \
rostest knowrob_ros test_knowrob_ros_lib.test \
"
19 changes: 7 additions & 12 deletions scripts/test_knowrob_ros_lib.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,11 +3,12 @@
"""
test_knowrob_ros_lib.py

Unit tests for KnowRobRosLib, now including incremental-query support.
Unit tests for KnowRobRosLib, including AskOne, AskAll, Incremental, and Tell.
"""

import unittest
import rosunit
import rospy

from knowrob_ros.knowrob_ros_lib import (
KnowRobRosLib,
Expand All @@ -33,17 +34,18 @@ class TestKnowrobRosLib(unittest.TestCase):
@classmethod
def setUpClass(cls):
"""
Initialize KnowRobRosLib and ROS node once for all tests.
Initialize ROS node and KnowRobRosLib once for all tests.
"""
rospy.init_node("test_knowrob_ros_lib", anonymous=True)
cls.knowrob_ros = KnowRobRosLib()
cls.knowrob_ros.init_node("test_knowrob_ros_lib")
cls.knowrob_ros.init_clients()

@classmethod
def tearDownClass(cls):
"""
Shutdown ROS node after all tests.
Shutdown KnowRobRosLib after all tests.
"""
cls.knowrob_ros.shutdown_node()
cls.knowrob_ros.shutdown()

def test_ask_all(self):
"""AskAll should return all matches for a query."""
Expand Down Expand Up @@ -113,13 +115,6 @@ def test_ask_incremental(self):
self.assertTrue(finished)


# Note: stray free-standing setUpClass below is a duplicate and has no effect on tests.
@classmethod
def setUpClass(cls):
cls.knowrob_ros = KnowRobRosLib()
cls.knowrob_ros.init_node("test_knowrob_ros_lib")


if __name__ == '__main__':
rosunit.unitrun(
'knowrob_ros', # package name
Expand Down
159 changes: 69 additions & 90 deletions src/knowrob_ros_lib/knowrob_ros_lib.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,32 +4,21 @@
knowrob_ros_lib.py

A simple wrapper around KnowRob ROS actionlib services.
Provides methods to initialize the ROS node and to call AskOne, AskAll, AskIncremental, and Tell actions,
Provides methods to call AskOne, AskAll, AskIncremental, and Tell actions,
as well as utility functions for working with modal frames and GraphAnswerMessages.
Now decoupled from rospy.init_node() to allow safer integration in ROS nodes.
"""

import actionlib
import rospy

from knowrob_ros.msg import (
AskAllAction,
AskAllGoal,
AskAllResult,
AskIncrementalAction,
AskIncrementalGoal,
AskIncrementalNextSolutionAction,
AskIncrementalNextSolutionGoal,
AskOneAction,
AskOneGoal,
AskOneResult,
GraphAnswerMessage,
GraphQueryMessage,
KeyValuePair,
ModalFrame,
TellAction,
TellGoal,
TellResult,
Triple,
AskAllAction, AskAllGoal, AskAllResult,
AskIncrementalAction, AskIncrementalGoal,
AskIncrementalNextSolutionAction, AskIncrementalNextSolutionGoal,
AskOneAction, AskOneGoal, AskOneResult,
GraphAnswerMessage, GraphQueryMessage, KeyValuePair, ModalFrame,
TellAction, TellGoal, TellResult, Triple,
)
from knowrob_ros.srv import AskIncrementalFinish

Expand All @@ -38,20 +27,16 @@ class KnowRobRosLib:
"""
Wrapper for KnowRob ROS services using actionlib.

Methods:
init_node(name): Initialize ROS node, action clients, and services.
shutdown_node(): Shutdown ROS node and cancel all goals.
ask_one(query, modal_frame, lang): Single-result query.
ask_all(query, modal_frame, lang): Multi-result query.
ask_incremental(query, modal_frame, lang): Start an incremental query.
next_solution(query_id): Retrieve next solution from an incremental query.
finish_incremental(query_id): Finish an incremental query.
tell(triples, modal_frame): Assert triples into the knowledge base.
Usage:
roslib = KnowRobRosLib()
roslib.init_clients() # After rospy.init_node()
result = roslib.ask_one("someQuery", get_default_modalframe())
"""

def __init__(self):
"""
Initialize client and service placeholders. Call init_node() before use.
Initialize client and service placeholders.
Use init_clients() to connect to action servers.
"""
self._ask_one_client = None
self._ask_all_client = None
Expand All @@ -60,51 +45,37 @@ def __init__(self):
self._tell_client = None
self._ask_incremental_finish = None

def init_node(self, name):
def init_clients(self):
"""
Initialize the ROS node and all actionlib clients and services.

Args:
name (str): Name for the ROS node.
Initialize all actionlib clients and service proxies.
Does NOT call rospy.init_node(). Call that yourself before this.
"""
rospy.init_node(name, anonymous=True)
rospy.loginfo("Initializing KnowRob ROS action clients...")

# AskOne
self._ask_one_client = actionlib.SimpleActionClient(
'knowrob/askone', AskOneAction)
self._ask_one_client.wait_for_server()
self._ask_one_client = actionlib.SimpleActionClient('knowrob/askone', AskOneAction)
self._ask_all_client = actionlib.SimpleActionClient('knowrob/askall', AskAllAction)
self._ask_incremental_client = actionlib.SimpleActionClient('knowrob/askincremental', AskIncrementalAction)
self._ask_incremental_next_client = actionlib.SimpleActionClient(
'knowrob/askincremental_next_solution', AskIncrementalNextSolutionAction)
self._tell_client = actionlib.SimpleActionClient('knowrob/tell', TellAction)

# AskAll
self._ask_all_client = actionlib.SimpleActionClient(
'knowrob/askall', AskAllAction)
# Wait for all servers
self._ask_one_client.wait_for_server()
self._ask_all_client.wait_for_server()

# AskIncremental (start)
self._ask_incremental_client = actionlib.SimpleActionClient(
'knowrob/askincremental', AskIncrementalAction)
self._ask_incremental_client.wait_for_server()

# AskIncremental (next solution)
self._ask_incremental_next_client = actionlib.SimpleActionClient(
'knowrob/askincremental_next_solution', AskIncrementalNextSolutionAction)
self._ask_incremental_next_client.wait_for_server()

# Tell
self._tell_client = actionlib.SimpleActionClient(
'knowrob/tell', TellAction)
self._tell_client.wait_for_server()

# Finish incremental query service
rospy.loginfo("Waiting for KnowRob service: askincremental_finish...")
rospy.wait_for_service('knowrob/askincremental_finish')
self._ask_incremental_finish = rospy.ServiceProxy(
'knowrob/askincremental_finish', AskIncrementalFinish)
self._ask_incremental_finish = rospy.ServiceProxy('knowrob/askincremental_finish', AskIncrementalFinish)

rospy.loginfo("KnowRob action clients and services initialized.")

def shutdown_node(self):
def shutdown(self):
"""
Shutdown the ROS node and cancel any pending goals.
Cancel pending goals. Optionally call rospy.signal_shutdown separately if needed.
"""
rospy.signal_shutdown('KnowRob node shutdown')

for client in (
self._ask_one_client,
self._ask_all_client,
Expand All @@ -119,6 +90,11 @@ def ask_one(self, query, modal_frame, lang=GraphQueryMessage.LANG_FOL):
"""
Send an AskOne query to KnowRob and wait for a single result.

Args:
query (str): Query string in FOL or Prolog syntax.
modal_frame (ModalFrame): Context of the query.
lang (int): Query language (default: LANG_FOL).

Returns:
AskOneResult
"""
Expand Down Expand Up @@ -149,8 +125,8 @@ def ask_all(self, query, modal_frame, lang=GraphQueryMessage.LANG_FOL):

def ask_incremental(self, query, modal_frame, lang=GraphQueryMessage.LANG_FOL):
"""
Start an incremental query. The server returns a status and a queryId
that can be used to fetch solutions one by one.
Start an incremental query. The server returns a queryId
to retrieve solutions one-by-one.

Returns:
AskIncrementalResult
Expand All @@ -166,10 +142,10 @@ def ask_incremental(self, query, modal_frame, lang=GraphQueryMessage.LANG_FOL):

def next_solution(self, query_id):
"""
Retrieve the next solution for an active incremental query.
Retrieve the next solution from an incremental query.

Args:
query_id (int): ID from ask_incremental().
query_id (int): ID returned by ask_incremental()

Returns:
AskIncrementalNextSolutionResult
Expand All @@ -183,20 +159,20 @@ def next_solution(self, query_id):

def finish_incremental(self, query_id):
"""
Finish an incremental query, releasing server-side resources.

Args:
query_id (int): ID from ask_incremental().
Finish an incremental query and release server-side resources.

Returns:
bool: True if the finish call succeeded.
bool: Success status.
"""
resp = self._ask_incremental_finish(query_id)
return resp.success
return self._ask_incremental_finish(query_id).success

def tell(self, list_of_triples, modal_frame):
"""
Send a set of RDF-style triples to the KnowRob knowledge base.
Send RDF-style triples to KnowRob to assert knowledge.

Args:
list_of_triples (list of Triple): Triples to insert.
modal_frame (ModalFrame): Context.

Returns:
TellResult
Expand All @@ -210,9 +186,13 @@ def tell(self, list_of_triples, modal_frame):
return self._tell_client.get_result()


# ------------------------------
# Helper Functions
# ------------------------------

def get_default_modalframe():
"""
Create a default ModalFrame with knowledge, current time, and unspecified timestamps.
Create a default ModalFrame with epistemic and temporal context.

Returns:
ModalFrame
Expand All @@ -228,7 +208,13 @@ def get_default_modalframe():

def graph_answer_to_dict(answer_msg):
"""
Convert a GraphAnswerMessage into a Python dict mapping variable names to values.
Convert a GraphAnswerMessage into a Python dictionary.

Args:
answer_msg (GraphAnswerMessage)

Returns:
dict: Variable bindings.
"""
results = {}
for kv in answer_msg.substitution:
Expand All @@ -253,40 +239,33 @@ def graph_answer_to_dict(answer_msg):

def graph_answers_to_list(answer_msgs):
"""
Convert multiple GraphAnswerMessages into a list of dicts.
Convert a list of GraphAnswerMessages to a list of dicts.

Returns:
list of dict
"""
return [graph_answer_to_dict(msg) for msg in answer_msgs]


class TripleQueryBuilder:
"""
Helper to build lists of Triple messages for assertions.
Usage:
Helper class to construct lists of Triple messages for Tell.

Example:
builder = TripleQueryBuilder()
builder.add(subject, predicate, object)
builder.add("s", "p", "o")
triples = builder.get_triples()
"""

def __init__(self):
self.triples = []

def add(self, subject, predicate, obj):
"""
Add a new Triple to the builder.

Args:
subject (str)
predicate (str)
obj (str)
"""
triple = Triple()
triple.subject = subject
triple.predicate = predicate
triple.object = obj
self.triples.append(triple)

def get_triples(self):
"""
Return the collected triples.
"""
return self.triples