diff --git a/moveit_py/docs/source/index.rst b/moveit_py/docs/source/index.rst index 104580cc28..9d598f9ae2 100644 --- a/moveit_py/docs/source/index.rst +++ b/moveit_py/docs/source/index.rst @@ -9,4 +9,5 @@ MoveItPy API Documentation moveit_py.core moveit_py.planning + moveit_py.policies moveit_py.servo_client diff --git a/moveit_py/moveit/policies/__init__.py b/moveit_py/moveit/policies/__init__.py index 53e7dff01b..d6e57cf6f9 100644 --- a/moveit_py/moveit/policies/__init__.py +++ b/moveit_py/moveit/policies/__init__.py @@ -1 +1,6 @@ +"""Utilities for learned policy deployment. + +This module can be used to configure moveit_servo for learning based applications. +""" + from .policy import Policy diff --git a/moveit_py/moveit/policies/__init__.pyi b/moveit_py/moveit/policies/__init__.pyi new file mode 100644 index 0000000000..e69de29bb2 diff --git a/moveit_py/moveit/policies/policy.py b/moveit_py/moveit/policies/policy.py index 24e1f70a5a..907308ce0a 100644 --- a/moveit_py/moveit/policies/policy.py +++ b/moveit_py/moveit/policies/policy.py @@ -39,7 +39,6 @@ from abc import ABC, abstractmethod -import rclpy from rclpy.node import Node from rclpy.qos import QoSProfile @@ -66,7 +65,7 @@ def __init__(self, params, node_name="policy_node"): # set policy to inactive by default self._is_active = False - self.activate_policy = self.create_service( + self.activate_policy_service = self.create_service( SetBool, "activate_policy", self.activate_policy, @@ -98,7 +97,7 @@ def get_sensor_msg_type(self, msg_type): if msg_type == "sensor_msgs/Image": return Image else: - raise ValueError(f"Sensor type {sensor_type} not supported.") + raise ValueError(f"Sensor type {msg_type} not supported.") def get_command_msg_type(self, msg_type): """Returns the ROS 2 message type for a given command type.""" diff --git a/moveit_py/moveit/policies/policy.pyi b/moveit_py/moveit/policies/policy.pyi new file mode 100644 index 0000000000..c26c12fc38 --- /dev/null +++ b/moveit_py/moveit/policies/policy.pyi @@ -0,0 +1,21 @@ +import abc +from abc import ABC, abstractmethod +from rclpy.node import Node +from typing import Any + +class Policy(ABC, Node, metaclass=abc.ABCMeta): + logger: Any + param_listener: Any + params: Any + activate_policy_service: Any + _is_active: bool + def __init__(self, params, node_name) -> None: ... + @property + def is_active(self) -> Any: ... + def activate_policy(self, request: Any, response: Any) -> Any: ... + def get_sensor_msg_type(self, msg_type: str) -> Any: ... + def get_command_msg_type(self, msg_type: str) -> Any: ... + def register_sensors(self): ... + def register_command(self): ... + @abstractmethod + def forward(self): ...