Skip to content

Commit

Permalink
Fixes from review.
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette committed May 16, 2023
1 parent 13684f3 commit 936ea3c
Show file tree
Hide file tree
Showing 5 changed files with 14 additions and 23 deletions.
11 changes: 11 additions & 0 deletions ros2cli/ros2cli/helpers.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from argparse import ArgumentTypeError
import functools
import inspect
import os
Expand Down Expand Up @@ -96,3 +97,13 @@ def wrapper(*args, **kwargs):
return func(*args, **kwargs)
wrapper.__signature__ = inspect.signature(func)
return wrapper


def unsigned_int(string):
try:
value = int(string)
except ValueError:
value = -1
if value < 0:
raise ArgumentTypeError('value must be non-negative integer')
return value
2 changes: 1 addition & 1 deletion ros2service/ros2service/api/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ def get_service_class(node: Node, service_name: str, include_hidden_services: bo
The service should be running for this function to find the service type.
:param node: The node object of rclpy Node class.
:param service_name: The name of the service.
:param service_name: The fully-qualified name of the service.
:param include_hidden_services: Whether to include hidden services while finding the
list of currently running services.
:return:
Expand Down
12 changes: 1 addition & 11 deletions ros2service/ros2service/verb/echo.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,12 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from argparse import ArgumentTypeError
from typing import TypeVar

import rclpy

from rclpy.qos import QoSPresetProfiles
from ros2cli.helpers import unsigned_int
from ros2cli.node.strategy import NodeStrategy
from ros2service.api import get_service_class
from ros2service.api import ServiceNameCompleter
Expand All @@ -32,16 +32,6 @@
MsgType = TypeVar('MsgType')


def unsigned_int(string):
try:
value = int(string)
except ValueError:
value = -1
if value < 0:
raise ArgumentTypeError('value must be non-negative integer')
return value


class EchoVerb(VerbExtension):
"""Echo a service."""

Expand Down
10 changes: 0 additions & 10 deletions ros2topic/ros2topic/api/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,16 +29,6 @@
from rosidl_runtime_py.utilities import get_message


def unsigned_int(string):
try:
value = int(string)
except ValueError:
value = -1
if value < 0:
raise ArgumentTypeError('value must be non-negative integer')
return value


def positive_int(string):
try:
value = int(string)
Expand Down
2 changes: 1 addition & 1 deletion ros2topic/ros2topic/verb/echo.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,14 +24,14 @@
from rclpy.qos import QoSProfile
from rclpy.qos import QoSReliabilityPolicy
from rclpy.task import Future
from ros2cli.helpers import unsigned_int
from ros2cli.node.strategy import add_arguments as add_strategy_node_arguments
from ros2cli.node.strategy import NodeStrategy
from ros2topic.api import add_qos_arguments
from ros2topic.api import get_msg_class
from ros2topic.api import positive_float
from ros2topic.api import qos_profile_from_short_keys
from ros2topic.api import TopicNameCompleter
from ros2topic.api import unsigned_int
from ros2topic.verb import VerbExtension
from rosidl_runtime_py import message_to_csv
from rosidl_runtime_py import message_to_yaml
Expand Down

0 comments on commit 936ea3c

Please sign in to comment.