Skip to content

Commit

Permalink
Merge branch 'release/0.10.0'
Browse files Browse the repository at this point in the history
  • Loading branch information
jara001 committed Mar 4, 2024
2 parents 578be78 + c235358 commit 8c61dd3
Show file tree
Hide file tree
Showing 8 changed files with 522 additions and 2 deletions.
13 changes: 13 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,19 @@ All notable changes to this project will be documented in this file.
The format is based on [Keep a Changelog](http://keepachangelog.com/).

## Unreleased
## 0.10.0 - 2024-03-04
### Added
- `qos`:
- Wrapper for importing the QoS settings in the same way as `rclpy`.
- `time`:
- New module for measuring duration of code snippets. Port from `rosmeasure` ROS package.
- `uninode`
- Module `duration` with class `Duration` that is used for timestamps in the messages.

### Fixed
- `uninode`
- `Time()` now works properly in ROS2.

## 0.9.5 - 2023-10-17
### Fixed
- `uninode`
Expand Down
81 changes: 81 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@ Currently, this package contains following modules:
- [reconfigure](#reconfigure-module)
- [uninode](#uninode-module)
- [unicore](#unicore-module)
- qos (a wrapper to support `autopsy.qos`)
- [time](#time-module)



Expand Down Expand Up @@ -403,9 +405,21 @@ Universal core layer for both ROS 1 and ROS 2.

Universal core (or unicore) serves as a compatibility layer for running a ROS node that is executable from both ROS versions.

- [Features](#features)
- [Example](#full-example-2)


### Features

Here follows a list of implemented functions from 'rospy'/'rclpy':
- (ROS2) init()
- spin()
- (ROS2) spin_once()
- (ROS2) spin_until_future_complete()
- (ROS2) shutdown()
- duration.Duration() -- Duration is used to store stamps inside the messages. The opposite action is not yet implemented.


### Full example

Example:
Expand All @@ -428,3 +442,70 @@ n.Subscriber("/topic", Int32, callback)

Core.spin(n)
```



## Time module

Set of utilities for measuring duration of code blocks. This was originally a part of `rosmeasure` package.

- [Classes](#classes)
- [Decorators](#decorators)


### Classes
The autopsy.time utility currently provides following classes:
- TimeMeasurer


#### TimeMeasurer

TimeMeasurer measures time spend in the selected section of the
code. It is created as:

```py
tm = TimeMeasurer(
name = "Measurer", # Name of the Measurer
units = "s" # Time units used for the measuring
)
```

Upon creation, these functions are used:
- `start()` -- Starts the measurement.
- `end()` -- Ends the measurement, storing the values inside.
- `summary()` -- Prints out the statistics for the Measurer.

Another way of using this measurer is as follows:

```py
with TimeMeasurer(name, units) as _ :
...
```

### Decorators
The autopsy.time utility also provides decorators to be used
instead of the classes:
- @duration


#### @duration

Duration decorator is basically the same as TimeMeasurer. It
is used as follows:

```py
@duration(name, units)
def function():
pass
```

The decorator supplies following section of the code:

```py
TM = TimeMeasurer(name, units)
TM.start()
output = function()
TM.end()
TM.summary()
return output
```
6 changes: 6 additions & 0 deletions autopsy/core.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,15 @@
import rospy

ROS_VERSION = 1

import autopsy.ros1_duration as duration
except:
try:
import rclpy

ROS_VERSION = 2

import rclpy.duration as duration
except:
print ("No ROS package detected.")
ROS_VERSION = 0
Expand Down Expand Up @@ -83,6 +87,8 @@ def ros2_only(f):
class Core(object):
"""Universal core class that supports both ROS 1 and ROS 2."""

duration = duration

@ros2_only
def init(self, args = None, context = None):
"""Initialize ROS communications for a given context.
Expand Down
3 changes: 2 additions & 1 deletion autopsy/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -97,6 +97,7 @@ def topic_callback(self, msg):

elif ROS_VERSION == 2:
from rclpy.node import Node as NodeI
from rclpy.time import Time as TimeI
from rclpy.qos import *
from .ports import rclpy_wait_for_message

Expand Down Expand Up @@ -214,7 +215,7 @@ def Time(self, secs = 0, nsecs = 0):
3) If nsecs is lower than 0, reduce secs to make it positive.
In ROS2, class does not care. Time is stored in nanoseconds.
"""
return TimeI(secs, nsecs)
return TimeI(seconds = secs, nanoseconds = nsecs)


def get_time(self):
Expand Down
18 changes: 18 additions & 0 deletions autopsy/qos.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
#!/usr/bin/env python
# qos.py
"""Wrapper for QoS classes for ROS1.
This serves as a way to import QoSProfile and related classes without specific
ROS version.
"""
######################
# Imports & Globals
######################

from autopsy.core import ROS_VERSION

if ROS_VERSION == 1:
from .ros1_qos import *

else: # ROS_VERSION == 2
from rclpy.qos import *
114 changes: 114 additions & 0 deletions autopsy/ros1_duration.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,114 @@
#!/usr/bin/env python
# duration.py
"""ROS2 Duration compatible implementation for ROS1.
"""
######################
# Imports & Globals
######################

from rospy import Duration as DurationR1

CONVERSION_CONSTANT = 10 ** 9


######################
# Duration class
######################

class Duration(object):
"""Duration class to mimic ROS2 `Duration`.
Reference:
https://github.com/ros2/rclpy/blob/humble/rclpy/rclpy/duration.py
"""

def __init__(self, *, seconds=0, nanoseconds=0):
"""Initialize the class.
Arguments:
seconds -- number of seconds, float
nanoseconds -- number of nanoseconds, int
Reference:
https://github.com/ros2/rclpy/blob/humble/rclpy/rclpy/duration.py
"""
self.total_nanoseconds = int(seconds * CONVERSION_CONSTANT)
self.total_nanoseconds += int(nanoseconds)

if self.total_nanoseconds >= 2**63 or self.total_nanoseconds < -2**63:
# pybind11 would raise TypeError, but we want OverflowError
# We keep it here for some ROS version consistency.
raise OverflowError(
'Total nanoseconds value is too large to store in C duration.'
)

@property
def nanoseconds(self):
return self.total_nanoseconds


def to_msg(self):
"""Convert the object into ROS message."""
return DurationR1(
secs = self.nanoseconds // CONVERSION_CONSTANT,
nsecs = self.nanoseconds % CONVERSION_CONSTANT
)


@classmethod
def from_msg(cls, msg, **kwargs):
"""Obtain Duration from a message.
TODO: Not sure how this one translates to ROS 1.
"""
return NotImplemented


def get_c_duration(self):
return NotImplemented


## Operators ##
# Source: https://github.com/ros2/rclpy/blob/humble/rclpy/rclpy/duration.py
def __repr__(self):
return 'Duration(nanoseconds=%d)' % self.nanoseconds

def __str__(self):
if self == Infinite:
return 'Infinite'
return '%d nanoseconds' % self.nanoseconds

def __eq__(self, other):
if isinstance(other, Duration):
return self.nanoseconds == other.nanoseconds
# Raise instead of returning NotImplemented to prevent comparison with invalid types,
# e.g. ints.
# Otherwise `Duration(nanoseconds=5) == 5` will return False instead of raising, and this
# could lead to hard-to-find bugs.
raise TypeError("Can't compare duration with object of type: ", type(other))

def __ne__(self, other):
return not self.__eq__(other)

def __lt__(self, other):
if isinstance(other, Duration):
return self.nanoseconds < other.nanoseconds
return NotImplemented

def __le__(self, other):
if isinstance(other, Duration):
return self.nanoseconds <= other.nanoseconds
return NotImplemented

def __gt__(self, other):
if isinstance(other, Duration):
return self.nanoseconds > other.nanoseconds
return NotImplemented

def __ge__(self, other):
if isinstance(other, Duration):
return self.nanoseconds >= other.nanoseconds
return NotImplemented


Infinite = Duration(seconds = -1)
Loading

0 comments on commit 8c61dd3

Please sign in to comment.