Skip to content

Commit

Permalink
Deleted ROS2-related files (#33)
Browse files Browse the repository at this point in the history
* fix: deleted all ROS2-related files
fix: shortened CMakeLists to avoid linking with ROS2 libs
feat: added type hints to all python files
  • Loading branch information
dfbakin authored Jul 4, 2024
1 parent 3bc2760 commit b89b867
Show file tree
Hide file tree
Showing 13 changed files with 27 additions and 355 deletions.
19 changes: 4 additions & 15 deletions packages/camera/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,25 +4,15 @@ project(camera)
add_compile_options(-Wall -Wextra -Werror=unused-variable -Wpedantic)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -pthread")

find_package(cv_bridge REQUIRED)
# find_package(cv_bridge REQUIRED)
find_package(OpenCV REQUIRED)
find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(std_srvs REQUIRED)
find_package(foxglove_msgs REQUIRED)
find_package(visualization_msgs REQUIRED)
find_package(yaml_cpp_vendor REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(ament_cmake REQUIRED)
find_package(Boost REQUIRED)
find_package(camera_srvs REQUIRED)
find_package(common REQUIRED)

add_library(mvsdk SHARED IMPORTED)
set_target_properties(mvsdk PROPERTIES IMPORTED_LOCATION "/lib/libMVSDK.so")

add_library(queue_lib INTERFACE)

add_executable(camera src/camera.cpp src/camera_status.cpp)
add_executable(
calibration src/calibration_main.cpp src/calibration.cpp src/params.cpp
Expand All @@ -39,10 +29,9 @@ target_include_directories(
)

ament_target_dependencies(camera yaml_cpp_vendor)
ament_target_dependencies(calibration yaml_cpp_vendor Boost OpenCV)

ament_target_dependencies(calibration yaml_cpp_vendor Boost OpenCV camera_srvs)

target_link_libraries(camera mvsdk common::common)
target_link_libraries(camera mvsdk)

install(TARGETS camera DESTINATION lib/${PROJECT_NAME})

Expand Down
10 changes: 0 additions & 10 deletions packages/camera/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,19 +9,9 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>cv_bridge</depend>
<depend>OpenCV</depend>
<depend>rclcpp</depend>
<depend>sensor_msgs</depend>
<depend>std_msgs</depend>
<depend>std_srvs</depend>
<depend>visuallization_msgs</depend>
<depend>foxglove_msgs</depend>
<depend>geometry_msgs</depend>
<depend>yaml_cpp_vendor</depend>
<depend>Boost</depend>
<depend>camera_srvs</depend>
<depend>common</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
10 changes: 7 additions & 3 deletions packages/camera/scripts/binary_parser.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,12 +7,16 @@
from tqdm import tqdm


def save_image(i, img_data, output_folder, width, height):
def save_image(
i: int, img_data: bytes, output_folder: str, width: int, height: int
) -> None:
img = np.frombuffer(img_data, dtype=np.uint8).reshape((height, width))
cv2.imwrite(os.path.join(output_folder, f"image_{str(i).rjust(4, '0')}.png"), img)


def read_and_convert(file_path, output_folder, width=1920, height=1200):
def read_and_convert(
file_path: str, output_folder: str, width=1920, height=1200
) -> None:
if not os.path.exists(output_folder):
os.makedirs(output_folder)

Expand All @@ -30,7 +34,7 @@ def read_and_convert(file_path, output_folder, width=1920, height=1200):
# save_image(i, img_data, output_folder, width, height)


def init_parser():
def init_parser() -> argparse.ArgumentParser:
parser = argparse.ArgumentParser()

parser.add_argument(
Expand Down
13 changes: 8 additions & 5 deletions packages/camera/scripts/dataset_creator.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
import argparse
import os
from typing import List

import cv2
import numpy as np
Expand All @@ -11,7 +12,9 @@


class Intrinsics:
def __init__(self, camera_matrix, dist_coefs, image_size):
def __init__(
self, camera_matrix: np.ndarray, dist_coefs: np.ndarray, image_size: List[int]
) -> None:
self.camera_matrix = camera_matrix
self.dist_coefs = dist_coefs
self.image_size = image_size
Expand All @@ -24,7 +27,7 @@ def __init__(self, camera_matrix, dist_coefs, image_size):
5,
)

def undistort_image(self, image):
def undistort_image(self, image: np.ndarray) -> np.ndarray:
cur_image_size = image.shape[:2]
assert self.image_size == cur_image_size, (
"Images of different sizes were provided: "
Expand All @@ -34,7 +37,7 @@ def undistort_image(self, image):
return cv2.remap(image, self.mapx, self.mapy, cv2.INTER_NEAREST)

@staticmethod
def create_from_yaml(path_to_file):
def create_from_yaml(path_to_file: str):
if not os.path.isfile(path_to_file):
raise FileNotFoundError
with open(path_to_file, "r") as stream:
Expand All @@ -48,7 +51,7 @@ def create_from_yaml(path_to_file):
return Intrinsics(camera_matrix, dist_coefs, image_size)


def init_parser():
def init_parser() -> argparse.ArgumentParser:
parser = argparse.ArgumentParser()

parser.add_argument("--source", help="Directory with raw distorted images")
Expand All @@ -63,7 +66,7 @@ def init_parser():
return parser


def main():
def main() -> None:
intrinsic_params = None
parser = init_parser()
args = parser.parse_args()
Expand Down
14 changes: 8 additions & 6 deletions packages/camera/scripts/rosbag_parser.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,9 @@
import argparse
import os
from typing import List

import cv2
import numpy as np # for type honts
import rosbag2_py
from cv_bridge import CvBridge
from rclpy.serialization import deserialize_message
Expand All @@ -10,21 +12,21 @@
FRAME_SIZE = (1024, 1280)


def get_type_by_topic(bag_topics):
def get_type_by_topic(bag_topics: List[rosbag2_py.TopicMetadata]) -> str:
type_by_topic = {}
for topic in bag_topics:
type_by_topic[topic.name] = topic.type
return type_by_topic


def topic_to_dir(name):
def topic_to_dir(name: str) -> str:
dir_name = name.replace("/", "_")
if dir_name[0] == "_":
dir_name = dir_name[1:]
return dir_name


def create_dirs(save_dir, topics, equalise=False):
def create_dirs(save_dir: str, topics: List[str], equalise=False) -> None:
if not os.path.exists(save_dir):
os.mkdir(save_dir)

Expand All @@ -39,7 +41,7 @@ def create_dirs(save_dir, topics, equalise=False):
os.mkdir(full_dir)


def equalise_hist(img):
def equalise_hist(img: np.ndarray) -> np.ndarray:
if len(img.shape) == 3:
for i in range(3):
img[:, :, i] = cv2.equalizeHist(img[:, :, i])
Expand All @@ -51,7 +53,7 @@ def equalise_hist(img):
return img


def init_parser():
def init_parser() -> argparse.ArgumentParser:
parser = argparse.ArgumentParser()
parser.add_argument("--topics", nargs="*")
parser.add_argument("--from-bag")
Expand All @@ -61,7 +63,7 @@ def init_parser():
return parser


def main():
def main() -> None:
parser = init_parser()
args = parser.parse_args()

Expand Down
15 changes: 0 additions & 15 deletions packages/camera_srvs/CMakeLists.txt

This file was deleted.

22 changes: 0 additions & 22 deletions packages/camera_srvs/package.xml

This file was deleted.

7 changes: 0 additions & 7 deletions packages/camera_srvs/srv/CalibrationCommand.srv

This file was deleted.

31 changes: 0 additions & 31 deletions packages/common/CMakeLists.txt

This file was deleted.

89 changes: 0 additions & 89 deletions packages/common/include/lock_free_queue.h

This file was deleted.

23 changes: 0 additions & 23 deletions packages/common/package.xml

This file was deleted.

Loading

0 comments on commit b89b867

Please sign in to comment.