Skip to content

Commit 865f5aa

Browse files
committed
Build as python package so we can test with colcon
1 parent 45a2881 commit 865f5aa

18 files changed

+53
-48
lines changed

mocha_core/CMakeLists.txt

Lines changed: 11 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,15 @@ rosidl_generate_interfaces(${PROJECT_NAME}
2828
DEPENDENCIES std_msgs geometry_msgs vision_msgs builtin_interfaces
2929
)
3030

31-
# Install Python executables
31+
# Install Python package modules as library
32+
install(
33+
DIRECTORY mocha_core/
34+
DESTINATION ${PYTHON_INSTALL_DIR}/${PROJECT_NAME}
35+
FILES_MATCHING PATTERN "*.py"
36+
PATTERN "__pycache__" EXCLUDE
37+
)
38+
39+
# Install executables as scripts
3240
install(PROGRAMS
3341
mocha_core/integrate_database.py
3442
mocha_core/database_server.py
@@ -52,7 +60,7 @@ install(DIRECTORY config
5260
if(BUILD_TESTING)
5361
# find_package(ament_lint_auto REQUIRED)
5462
find_package(ament_cmake_pytest REQUIRED)
55-
63+
5664
# the following line skips the linter which checks for copyrights
5765
# comment the line when a copyright and license is added to all source files
5866
set(ament_cmake_copyright_FOUND TRUE)
@@ -61,7 +69,7 @@ if(BUILD_TESTING)
6169
# a copyright and license is added to all source files
6270
set(ament_cmake_cpplint_FOUND TRUE)
6371
# ament_lint_auto_find_test_dependencies()
64-
72+
6573
# Add Python tests
6674
ament_add_pytest_test(test_database test/test_database.py)
6775
ament_add_pytest_test(test_database_utils test/test_database_utils.py)

mocha_core/mocha_core/database.py

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,10 @@
11
#!/usr/bin/env python3
22
import threading
3-
import hash_comm
3+
import mocha_core.hash_comm as hash_comm
44
import rclpy.time
55
import pdb
6-
import database_utils as du
6+
import mocha_core.database_utils as du
77
import numpy as np
8-
import hash_comm
98
import copy
109

1110

mocha_core/mocha_core/database_server.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -6,9 +6,9 @@
66
import rclpy.logging
77
import rclpy.time
88
import mocha_core.srv
9-
import database
9+
import mocha_core.database as database
1010
import pdb
11-
import database_utils as du
11+
import mocha_core.database_utils as du
1212

1313

1414
class DatabaseServer:

mocha_core/mocha_core/database_utils.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,8 @@
11
import struct
22
import rclpy.time
33
import rclpy.logging
4-
import database as db
5-
import hash_comm
4+
import mocha_core.database as db
5+
import mocha_core.hash_comm as hash_comm
66
import io
77
import pdb
88
import importlib

mocha_core/mocha_core/integrate_database.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -14,9 +14,9 @@
1414
import std_msgs.msg
1515
import subprocess
1616

17-
import database_server as ds
18-
import database_utils as du
19-
import synchronize_channel as sync
17+
import mocha_core.database_server as ds
18+
import mocha_core.database_utils as du
19+
import mocha_core.synchronize_channel as sync
2020

2121

2222
def ping(host):

mocha_core/mocha_core/synchronize_channel.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -4,10 +4,10 @@
44
import threading
55
import time
66
import smach
7-
import database as db
8-
import database_utils as du
9-
import hash_comm as hc
10-
import zmq_comm_node
7+
import mocha_core.database as db
8+
import mocha_core.database_utils as du
9+
import mocha_core.hash_comm as hc
10+
import mocha_core.zmq_comm_node as zmq_comm_node
1111
import logging
1212
import rclpy
1313
import rclpy.logging

mocha_core/mocha_core/topic_publisher.py

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@
1010
import yaml
1111
import re
1212
import mocha_core.msg
13+
import mocha_core.database_utils as du
1314

1415
import mocha_core.srv
1516

@@ -181,9 +182,7 @@ def create_topic_publisher_node(robot_name, robot_configs_path=None, topic_confi
181182
current_dir = os.path.dirname(os.path.abspath(__file__))
182183
ddb_path = os.path.join(current_dir, "..")
183184

184-
# Add path for database_utils
185-
sys.path.append(os.path.join(ddb_path, "."))
186-
import database_utils as du
185+
# database_utils is imported at module level
187186

188187
# Get the robot_config path and generate the robot_configs object
189188
if robot_configs_path is None:

mocha_core/mocha_core/translator.py

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@ class Translator:
1313
def __init__(self, this_robot, this_robot_id,
1414
topic_name, topic_id, msg_type, node=None):
1515
# Get the database utils module
16-
import database_utils as du
16+
import mocha_core.database_utils as du
1717
self.__du = du
1818

1919
# Store or create the ROS2 node
@@ -115,9 +115,8 @@ def create_translator_node(robot_name, robot_configs_path=None, topic_configs_pa
115115
current_dir = os.path.dirname(os.path.abspath(__file__))
116116
ddb_path = os.path.join(current_dir, "..")
117117

118-
# Add path for database_utils
119-
sys.path.append(os.path.join(ddb_path, "."))
120-
import database_utils as du
118+
# Import database_utils from installed package
119+
import mocha_core.database_utils as du
121120

122121
# Get the robot_config path and generate the robot_configs object
123122
if robot_configs_path is None:

mocha_core/mocha_core/zmq_comm_node.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@
88
import rclpy.time
99
import rclpy.node
1010
import zmq
11-
import hash_comm
11+
import mocha_core.hash_comm as hash_comm
1212
import mocha_core.msg
1313

1414
HASH_LENGTH = hash_comm.Hash.HASH_LENGTH

mocha_core/test/sample_db.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -9,9 +9,9 @@
99
mocha_core_path = os.path.join(current_dir, "..", "mocha_core")
1010
sys.path.append(mocha_core_path)
1111

12-
import hash_comm
13-
import database as db
14-
import database_utils as du
12+
import mocha_core.hash_comm as hash_comm
13+
import mocha_core.database as db
14+
import mocha_core.database_utils as du
1515
import pdb
1616
import rclpy.time
1717

0 commit comments

Comments
 (0)