Skip to content

Commit

Permalink
Fix moveit_py Policy docs build (#2584)
Browse files Browse the repository at this point in the history
  • Loading branch information
sea-bass authored Dec 7, 2023
1 parent 3df6b28 commit 9129970
Show file tree
Hide file tree
Showing 5 changed files with 29 additions and 3 deletions.
1 change: 1 addition & 0 deletions moveit_py/docs/source/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -9,4 +9,5 @@ MoveItPy API Documentation

moveit_py.core
moveit_py.planning
moveit_py.policies
moveit_py.servo_client
5 changes: 5 additions & 0 deletions moveit_py/moveit/policies/__init__.py
Original file line number Diff line number Diff line change
@@ -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
Empty file.
5 changes: 2 additions & 3 deletions moveit_py/moveit/policies/policy.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,6 @@

from abc import ABC, abstractmethod

import rclpy
from rclpy.node import Node
from rclpy.qos import QoSProfile

Expand All @@ -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,
Expand Down Expand Up @@ -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."""
Expand Down
21 changes: 21 additions & 0 deletions moveit_py/moveit/policies/policy.pyi
Original file line number Diff line number Diff line change
@@ -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): ...

0 comments on commit 9129970

Please sign in to comment.