Skip to content

Commit

Permalink
[ontopy] fix ros2 compatibility
Browse files Browse the repository at this point in the history
  • Loading branch information
sarthou committed Jan 12, 2024
1 parent 299a495 commit 4b4c980
Show file tree
Hide file tree
Showing 9 changed files with 85 additions and 35 deletions.
7 changes: 7 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,13 @@ find_package(ament_cmake REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(rclcpp REQUIRED)
find_package(TinyXML2 REQUIRED)
find_package(ament_cmake_python REQUIRED)

#install(PROGRAMS
# ontopy/${PROJECT_NAME}
# DESTINATION lib)

ament_python_install_package(ontopy)
endif()

################################################
Expand Down
1 change: 1 addition & 0 deletions ontopy/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
from .ontologenius import *
8 changes: 6 additions & 2 deletions ontopy/ontologenius/ConversionClient.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,11 @@
from .compat.ros import Ontoros, OntoService
import os

from ontologenius.srv import OntologeniusConversion
from ontologenius.srv import OntologeniusConversionRequest
if os.environ["ROS_VERSION"] == "1":
from ontologenius.srv import OntologeniusConversionRequest
else:
from ontologenius.srv._ontologenius_conversion import OntologeniusConversion_Request as OntologeniusConversionRequest

class ConversionClient:

Expand Down Expand Up @@ -112,5 +116,5 @@ def _id2Index(self, id, source):
return None

def _call(self, source, values_str, values_int):
request = OntologeniusConversionRequest(source, values_str, values_int)
request = OntologeniusConversionRequest(source = source, values_str = values_str, values_int = values_int)
return self._client.call(request, self._verbose)
11 changes: 9 additions & 2 deletions ontopy/ontologenius/FeederPublisher.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,12 @@
from .compat.ros import Ontoros

import os

from std_msgs.msg import String
from ontologenius.msg import StampedString
if os.environ["ROS_VERSION"] == "1":
from ontologenius.msg import StampedString
else:
from ontologenius.msg import OntologeniusStampedString as StampedString

import time
import random
Expand Down Expand Up @@ -240,7 +246,8 @@ def _publish(self, data):
self._pub.publish(data)

def _publish_stamped(self, data, stamp):
self._stamped_pub.publish(data, stamp)
msg = StampedString(data = data, stamp = stamp)
self._stamped_pub.publish(msg)

def commitCallback(self, data):
if data.data == 'end':
Expand Down
18 changes: 12 additions & 6 deletions ontopy/ontologenius/clients/ClientBase.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,12 @@
from ..compat.ros import Ontoros, OntoService
from ..compat.ros import Ontoros
import os

from ontologenius.srv import OntologeniusService
if os.environ["ROS_VERSION"] == "1":
from ontologenius.srv import OntologeniusServiceRequest
else:
from ontologenius.srv._ontologenius_service import OntologeniusService_Request as OntologeniusServiceRequest

from ontologenius.srv import OntologeniusService, OntologeniusServiceRequest

class ClientBase:
"""The ClientBase class provides an abstraction for any ROS services.
Expand Down Expand Up @@ -37,7 +43,7 @@ def call(self, action, param):
If the service call fails, the function returns None
"""
ClientBase._cpt += 1
request = OntologeniusServiceRequest(action, param)
request = OntologeniusServiceRequest(action = action, param = param)
response = self._client.call(request, ClientBase._verbose)
if(response is None):
self.error_code = -1
Expand All @@ -52,7 +58,7 @@ def callStr(self, action, param):
If the service call fails, the function returns None
"""
ClientBase._cpt += 1
request = OntologeniusServiceRequest(action, param)
request = OntologeniusServiceRequest(action = action, param = param)
response = self._client.call(request, ClientBase._verbose)
if(response is None):
self.error_code = -1
Expand All @@ -70,7 +76,7 @@ def callNR(self, action, param):
If the service call fails, the function returns False
"""
ClientBase._cpt += 1
request = OntologeniusServiceRequest(action, param)
request = OntologeniusServiceRequest(action = action, param = param)
response = self._client.call(request, ClientBase._verbose)
if(response is None):
self.error_code = -1
Expand All @@ -86,7 +92,7 @@ def callBool(self, action, param):
service is different from SUCCESS.
"""
ClientBase._cpt += 1
request = OntologeniusServiceRequest(action, param)
request = OntologeniusServiceRequest(action = action, param = param)
response = self._client.call(request, ClientBase._verbose)
if(response is None):
self.error_code = -1
Expand Down
9 changes: 7 additions & 2 deletions ontopy/ontologenius/clients/SparqlClient.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,11 @@
from ..compat.ros import Ontoros, OntoService
import os

from ontologenius.srv import OntologeniusSparqlService, OntologeniusSparqlServiceRequest
from ontologenius.srv import OntologeniusSparqlService
if os.environ["ROS_VERSION"] == "1":
from ontologenius.srv import OntologeniusSparqlServiceRequest
else:
from ontologenius.srv._ontologenius_sparql_service import OntologeniusSparqlService_Request as OntologeniusSparqlServiceRequest

class SparqlClient:
"""The SparqlClient class provides a ROS service to explore ontologenius with SPARQL-like queries.
Expand All @@ -17,7 +22,7 @@ def __init__(self, name):
self._client = Ontoros.createService('ontologenius/' + self._name, OntologeniusSparqlService)

def call(self, query):
request = OntologeniusSparqlServiceRequest(query)
request = OntologeniusSparqlServiceRequest(query = query)
response = self._client.call(request)
if(response is None):
return None
Expand Down
19 changes: 12 additions & 7 deletions ontopy/ontologenius/clientsIndex/ClientBaseIndex.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,11 @@
from ..compat.ros import Ontoros, OntoService
import os

from ontologenius.srv import OntologeniusIndexService, OntologeniusIndexServiceRequest
from ontologenius.srv import OntologeniusIndexService
if os.environ["ROS_VERSION"] == "1":
from ontologenius.srv import OntologeniusIndexServiceRequest
else:
from ontologenius.srv._ontologenius_index_service import OntologeniusIndexService_Request as OntologeniusIndexServiceRequest

class ClientBaseIndex:
"""The ClientBaseIndex class provides an abstraction for any ROS services.
Expand Down Expand Up @@ -37,7 +42,7 @@ def call(self, action, param):
If the service call fails, the function returns None
"""
ClientBaseIndex._cpt += 1
request = OntologeniusIndexServiceRequest(action, param)
request = OntologeniusIndexServiceRequest(action = action, param = param)
response = self._client.call(request, ClientBaseIndex._verbose)
if(response is None):
self.error_code = -1
Expand All @@ -52,7 +57,7 @@ def callIndexes(self, action, param):
If the service call fails, the function returns None
"""
ClientBaseIndex._cpt += 1
request = OntologeniusIndexServiceRequest(action, param)
request = OntologeniusIndexServiceRequest(action = action, param = param)
response = self._client.call(request, ClientBaseIndex._verbose)
if(response is None):
self.error_code = -1
Expand All @@ -67,7 +72,7 @@ def callStr(self, action, param):
If the service call fails, the function returns None
"""
ClientBaseIndex._cpt += 1
request = OntologeniusIndexServiceRequest(action, param)
request = OntologeniusIndexServiceRequest(action = action, param = param)
response = self._client.call(request, ClientBaseIndex._verbose)
if(response is None):
self.error_code = -1
Expand All @@ -85,7 +90,7 @@ def callIndex(self, action, param):
If the service call fails, the function returns None
"""
ClientBaseIndex._cpt += 1
request = OntologeniusIndexServiceRequest(action, param)
request = OntologeniusIndexServiceRequest(action = action, param = param)
response = self._client.call(request, ClientBaseIndex._verbose)
if(response is None):
self.error_code = -1
Expand All @@ -103,7 +108,7 @@ def callNR(self, action, param):
If the service call fails, the function returns False
"""
ClientBaseIndex._cpt += 1
request = OntologeniusIndexServiceRequest(action, param)
request = OntologeniusIndexServiceRequest(action = action, param = param)
response = self._client.call(request, ClientBaseIndex._verbose)
if(response is None):
self.error_code = -1
Expand All @@ -119,7 +124,7 @@ def callBool(self, action, param):
service is different from SUCCESS.
"""
ClientBaseIndex._cpt += 1
request = OntologeniusIndexServiceRequest(action, param)
request = OntologeniusIndexServiceRequest(action = action, param = param)
response = self._client.call(request, ClientBaseIndex._verbose)
if(response is None):
self.error_code = -1
Expand Down
9 changes: 7 additions & 2 deletions ontopy/ontologenius/clientsIndex/SparqlIndexClient.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,11 @@
from ..compat.ros import Ontoros, OntoService
import os

from ontologenius.srv import OntologeniusSparqlIndexService, OntologeniusSparqlIndexServiceRequest
from ontologenius.srv import OntologeniusSparqlIndexService
if os.environ["ROS_VERSION"] == "1":
from ontologenius.srv import OntologeniusSparqlIndexServiceRequest
else:
from ontologenius.srv._ontologenius_sparql_index_service import OntologeniusSparqlIndexService_Request as OntologeniusSparqlIndexServiceRequest

class SparqlIndexClient:
"""The SparqlIndexClient class provides a ROS service to explore ontologenius with SPARQL-like queries based on indexes.
Expand All @@ -18,7 +23,7 @@ def __init__(self, name):


def call(self, query):
request = OntologeniusSparqlIndexServiceRequest(query)
request = OntologeniusSparqlIndexServiceRequest(query = query)
response = self._client.call(request)
if(response is None):
return None
Expand Down
38 changes: 24 additions & 14 deletions ontopy/ontologenius/compat/ros.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
import os
from ontologenius.msg import OntologeniusTimestamp

if os.environ["ROS_VERSION"] == "1":
import rospy
Expand Down Expand Up @@ -50,6 +51,9 @@ def __init__(self, sub_name, sub_type, callback):
def getNumPublishers(self):
self.sub.get_num_connections()

def unregister(self):
self.sub.unregister()

class Ontoros :
def createService(srv_name, srv_type):
return OntoService(srv_name, srv_type)
Expand All @@ -61,7 +65,7 @@ def createSubscriber(sub_name, sub_type, callback):
return OntoSubscriber(sub_name, sub_type, callback)

def getRosTime():
return rospy.get_rostime()
return rospy.get_rostime() # TODO

def isShutdown():
return rospy.is_shutdown()
Expand Down Expand Up @@ -114,20 +118,21 @@ def __call__(cls, *args, **kwargs):


class OntoService:
def __init__(self, client: Client, node_: Node):
def __init__(self, client: Client, name, node_: Node):
self.client: Client = client
self.node_: Node = node_
self.srv_name = name

def call(self, params: SrvTypeRequest) -> SrvTypeResponse:
def call(self, params: SrvTypeRequest, verbose) -> SrvTypeResponse:
future = self.client.call_async(request=params)
rclpy.spin_until_future_complete(self.node_, future)
return future.result()

def wait(self, timeout = -1): # TODO
def wait(self, timeout = -1):
if(timeout != -1):
self.client.wait_for_service(self.srv_name, timeout)
self.client.wait_for_service(timeout)
else:
self.client.wait_for_service(self.srv_name)
self.client.wait_for_service()


class OntoPublisher:
Expand All @@ -138,37 +143,42 @@ def publish(self, msg):
self.pub.publish(msg)

def getNumSubscribers(self):
self.pub.get_num_connections() # TODO
self.pub.get_num_connections()


class OntoSubscriber:
def __init__(self, sub):
self.sub: Subscription = sub

def getNumPublishers(self):
self.sub.get_num_connections() # TODO
self.sub.get_num_connections()

def unregister(self):
pass


class OntoROS(Node, metaclass=SingletonMeta):
class Ontoros(Node, metaclass=SingletonMeta):

def __init__(self):
super().__init__("OntoRos")

@staticmethod
def createService(srv_name, srv_type, connected) -> OntoService:
return OntoService(OntoROS().create_client(srv_name, srv_type), OntoROS())
def createService(srv_name, srv_type) -> OntoService:
return OntoService(Ontoros().create_client(srv_type, srv_name), srv_name, Ontoros())

@staticmethod
def createPublisher(pub_name, pub_type, queue_size: int) -> OntoPublisher:
return OntoPublisher(OntoROS().create_publisher(pub_type, pub_name, qos_profile=queue_size))
return OntoPublisher(Ontoros().create_publisher(pub_type, pub_name, qos_profile=queue_size))

@staticmethod
def createSubscriber(sub_name, sub_type, callback, queue_size: int = 10) -> OntoSubscriber:
return OntoSubscriber(OntoROS().create_subscription(sub_type, sub_name, callback, qos_profile=queue_size))
return OntoSubscriber(Ontoros().create_subscription(sub_type, sub_name, callback, qos_profile=queue_size))

@staticmethod
def getRosTime() -> Time:
return OntoROS().get_clock().now()
t_msg = Ontoros().get_clock().now().to_msg()
stamp_msg = OntologeniusTimestamp(seconds = t_msg._sec, nanoseconds = t_msg._nanosec)
return stamp_msg

@staticmethod
def isShutdown() -> bool:
Expand Down

0 comments on commit 4b4c980

Please sign in to comment.