Skip to content

Commit

Permalink
Merge remote-tracking branch 'github/main'
Browse files Browse the repository at this point in the history
  • Loading branch information
yiwenlu66 committed Dec 16, 2024
2 parents e62e207 + 839e48a commit 1e78eda
Show file tree
Hide file tree
Showing 5 changed files with 56 additions and 3 deletions.
38 changes: 38 additions & 0 deletions .github/workflows/build.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
name: GitHub Pages

on:
push:
branches: ["main"]

# 权限
permissions:
contents: write

jobs:
build-and-deploy:
runs-on: ubuntu-latest

steps:
- uses: actions/checkout@v3

- name: Set up Python
uses: actions/setup-python@v4
with:
python-version: 3.12

- name: Install dependencies
run: |
pip install -e .
pip install -e .[docs]
- name: Build Sphinx documentation
run: |
sphinx-build -b html docs build
# 创建 .nojekyll 文件以允许下划线开头的文件夹
touch build/.nojekyll
- name: Deploy to GitHub Pages
uses: JamesIves/[email protected]
with:
branch: gh-pages
folder: build
4 changes: 3 additions & 1 deletion ros_compat/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,9 @@
import rospy
ROS_VERSION = 1
except ImportError:
raise ImportError("Neither ROS1 (rospy) nor ROS2 (rclpy) was found")
import warnings
warnings.warn("Neither ROS1 (rospy) nor ROS2 (rclpy) was found")
ROS_VERSION = None

from .node import ROSNode
from .time import ROSTime
Expand Down
7 changes: 6 additions & 1 deletion ros_compat/logging.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,10 @@
try:
import rclpy as ros
except ImportError:
import rospy as ros
try:
import rospy as ros
except ImportError:
ros = None

class ROSLogger:
"""Wrapper for ROS logging functions.
Expand All @@ -16,6 +19,8 @@ class ROSLogger:
node_name (str): Name of the node for logging context
"""
def __init__(self, node_name: str):
if ROS_VERSION is None:
raise ImportError("Neither ROS1 (rospy) nor ROS2 (rclpy) was found")
self.node_name = node_name
if ROS_VERSION == 2:
self.logger = ros.logging.get_logger(node_name)
Expand Down
6 changes: 5 additions & 1 deletion ros_compat/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,12 @@
from rclpy.time import Time as ROS2Time
from rclpy.timer import Timer as ROS2Timer
from rclpy.qos import QoSProfile, ReliabilityPolicy
else:
elif ROS_VERSION == 1:
import rospy
ros = rospy # For consistent naming
from rospy import Time as ROS1Time
else:
ros = None

from .time import ROSTime
from .logging import ROSLogger
Expand All @@ -30,6 +32,8 @@ class ROSNode:
node_name (str): Name of the node
"""
def __init__(self, node_name: str):
if ROS_VERSION is None:
raise ImportError("Neither ROS1 (rospy) nor ROS2 (rclpy) was found")
self.node_name = node_name

if ROS_VERSION == 2:
Expand Down
4 changes: 4 additions & 0 deletions ros_compat/time.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,8 @@ def now(self) -> float:
>>> current_time = time.now()
>>> print(f"Current time: {current_time}")
"""
if ROS_VERSION is None:
raise ImportError("Neither ROS1 (rospy) nor ROS2 (rclpy) was found")
if ROS_VERSION == 2:
return float(self._node.get_clock().now().nanoseconds) / 1e9
return float(ros.Time.now().to_nsec()) / 1e9
Expand All @@ -58,6 +60,8 @@ def to_msg(self) -> Any:
@staticmethod
def sleep(duration: float) -> None:
"""Sleep for specified duration in seconds."""
if ROS_VERSION is None:
raise ImportError("Neither ROS1 (rospy) nor ROS2 (rclpy) was found")
if ROS_VERSION == 2:
ros.time.sleep(duration)
else:
Expand Down

0 comments on commit 1e78eda

Please sign in to comment.