Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat: python bindings for image_transport and publish #323

Merged
merged 27 commits into from
Oct 9, 2024
Merged
Changes from 1 commit
Commits
Show all changes
27 commits
Select commit Hold shift + click to select a range
c4d8434
feat: python bindings for image_transport and publish
tfoldi Sep 23, 2024
ac72a10
style: reformat code
tfoldi Sep 24, 2024
4f95097
style: missing headers, copyright year
tfoldi Sep 24, 2024
ff4ffd7
build: add tests
tfoldi Sep 24, 2024
8a4250c
build: remove pluginlib (not used)
tfoldi Sep 24, 2024
898d875
style: reformat with rolling ament config
tfoldi Sep 24, 2024
4ceb2ec
WIP: before moving spin to custom class
tfoldi Sep 26, 2024
591c0fe
doc: fix repository and bugtracker url
tfoldi Sep 26, 2024
2eddcbf
feat: camera_info and subscriber support
tfoldi Sep 26, 2024
4ba43b5
Merge branch 'feat_image_transport_py' of https://github.com/tfoldi/i…
tfoldi Sep 26, 2024
1d331ab
doc: create initial version of the README.md file
tfoldi Sep 26, 2024
74e32f1
doc: move README.md to the right location
tfoldi Sep 26, 2024
f3ece7d
feat: add image_transport parameter
tfoldi Sep 26, 2024
98042aa
doc: complete documentation
tfoldi Sep 27, 2024
1cc8b23
style: remove too long line
tfoldi Sep 27, 2024
03b8e9a
style: reformat
tfoldi Sep 27, 2024
d2983f8
style: fix documentation formating
tfoldi Sep 27, 2024
6b615d2
fix: CameraSubscriber class name
tfoldi Oct 1, 2024
0f0f3c7
build: move pybind11 to build only dep
tfoldi Oct 2, 2024
9246ea6
chore: implement review suggestions
tfoldi Oct 4, 2024
e6428ae
build: add <2.9 pybind11 compatibility
tfoldi Oct 8, 2024
6b802dd
Merge branch 'feat_image_transport_py' of https://github.com/tfoldi/i…
tfoldi Oct 8, 2024
e6e71f0
build: add <2.9 pybind11 compatibility
tfoldi Oct 8, 2024
2424f26
build: add <2.9 pybind11 compatibility
tfoldi Oct 8, 2024
817ed6c
build: ament_cppcheck(LANGUAGE "c++") after ament_lint_auto_find_test…
tfoldi Oct 8, 2024
7c1ea65
build: cpp check after test dependencies
tfoldi Oct 8, 2024
bf4eae9
build: skip cppcheck on Windows
tfoldi Oct 8, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Prev Previous commit
Next Next commit
feat: add image_transport parameter
tfoldi committed Sep 26, 2024
commit f3ece7d3b73e940c75b7f91485c2064d0d2eaa5a
Original file line number Diff line number Diff line change
@@ -78,7 +78,8 @@ PYBIND11_MODULE(_image_transport, m)
pybind11::class_<image_transport::ImageTransport>(m, "ImageTransport")
.def(
pybind11::init(
[](const std::string & node_name, const std::string & launch_params_filepath) {
[](const std::string & node_name, const std::string & image_transport,
const std::string & launch_params_filepath) {
if (!rclcpp::ok()) {
rclcpp::init(0, nullptr);
}
@@ -88,31 +89,42 @@ PYBIND11_MODULE(_image_transport, m)
node_options.allow_undeclared_parameters(true)
.automatically_declare_parameters_from_overrides(true)
.arguments({"--ros-args", "--params-file", launch_params_filepath});
} else if (!image_transport.empty()) {
node_options.allow_undeclared_parameters(true)
.automatically_declare_parameters_from_overrides(true)
.append_parameter_override("image_transport", image_transport);
}

rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(node_name, "", node_options);

std::shared_ptr<rclcpp::executors::MultiThreadedExecutor> executor =
std::make_shared<rclcpp::executors::MultiThreadedExecutor>();

auto spin_node = [node, executor]() {
executor->add_node(node);
executor->spin();
};
executor->add_node(node);
executor->spin();
};
std::thread execution_thread(spin_node);
execution_thread.detach();

return image_transport::ImageTransport(node);
}))
}),
pybind11::arg("node_name"), pybind11::arg("image_transport") = "",
pybind11::arg("launch_params_filepath") = "",

"Initialize an ImageTransport object with a node name and launch params file path.")
.def(
"advertise",
pybind11::overload_cast<const std::string &, uint32_t, bool>(
&image_transport::ImageTransport::advertise),
pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("latch") = false)
pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("latch") = false,
"Advertise an image topic.")
.def(
"advertise_camera",
pybind11::overload_cast<const std::string &, uint32_t, bool>(
&image_transport::ImageTransport::advertiseCamera),
pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("latch") = false)
pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("latch") = false,
"Advertise an image topic with camera info.")
.def(
"subscribe",
[](image_transport::ImageTransport & image_transport,
@@ -131,7 +143,8 @@ PYBIND11_MODULE(_image_transport, m)

return subscription;
},
pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("callback"))
pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("callback"),
"Subscribe to an image topic.")
.def(
"subscribe_camera",
[](image_transport::ImageTransport & image_transport,
@@ -150,7 +163,8 @@ PYBIND11_MODULE(_image_transport, m)

return subscription;
},
pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("callback"));
pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("callback"),
"Subscribe to an image topic with camera info.");

pybind11::class_<image_transport::Subscriber, std::shared_ptr<image_transport::Subscriber>>(
m,