Moving camera calib files to use camera#
Modifying intrinsics_calibration to handle and use this new format
Changing numbering to match /dev/video#, so that camera on /dev/video0
is publishing on /camera0 for example
Added a utility function to get camera number from channel, and a test to
go with it
Cleaned up some of the logging to use percentages instead of fractions /
decimals
Change-Id: I764d59ca7d9089a37d010272879ce55aae5dbd95
Signed-off-by: Jim Ostrowski <yimmy13@gmail.com>
diff --git a/frc971/vision/BUILD b/frc971/vision/BUILD
index 6cee780..02ab5e2 100644
--- a/frc971/vision/BUILD
+++ b/frc971/vision/BUILD
@@ -328,6 +328,7 @@
"//frc971/control_loops/drivetrain:improved_down_estimator",
"//frc971/vision:charuco_lib",
"//frc971/vision:vision_fbs",
+ "//frc971/vision:vision_util_lib",
"//frc971/wpilib:imu_batch_fbs",
"//frc971/wpilib:imu_fbs",
"//third_party:opencv",
@@ -374,3 +375,14 @@
"@com_github_google_glog//:glog",
],
)
+
+cc_test(
+ name = "vision_util_lib_test",
+ srcs = ["vision_util_lib_test.cc"],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//aos/testing:googletest",
+ "//frc971/vision:vision_util_lib",
+ "@com_github_google_glog//:glog",
+ ],
+)
diff --git a/frc971/vision/calibration.fbs b/frc971/vision/calibration.fbs
index df8b7b0..428fc83 100644
--- a/frc971/vision/calibration.fbs
+++ b/frc971/vision/calibration.fbs
@@ -48,6 +48,9 @@
// ID for the physical camera hardware (typically will be a string of the form
// YY-NN, with a two-digit year and an index).
camera_id:string (id: 7);
+
+ // The camera number. This may be empty, "0", or "1".
+ camera_number:int (id: 8);
}
// Calibration information for all the cameras we know about.
diff --git a/frc971/vision/intrinsics_calibration.cc b/frc971/vision/intrinsics_calibration.cc
index f98aadb..16a53a7 100644
--- a/frc971/vision/intrinsics_calibration.cc
+++ b/frc971/vision/intrinsics_calibration.cc
@@ -13,15 +13,17 @@
#include "aos/util/file.h"
#include "frc971/vision/intrinsics_calibration_lib.h"
-DEFINE_string(calibration_folder, ".", "Folder to place calibration files.");
-DEFINE_string(camera_id, "", "Camera ID in format YY-NN-- year and number.");
-DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
-DEFINE_bool(display_undistorted, false,
- "If true, display the undistorted image.");
-DEFINE_string(pi, "", "Pi name to calibrate.");
+// TODO: Would be nice to remove this, but it depends on year-by-year Constants
DEFINE_string(base_intrinsics, "",
"Intrinsics to use for estimating board pose prior to solving "
"for the new intrinsics.");
+DEFINE_string(calibration_folder, ".", "Folder to place calibration files.");
+DEFINE_string(camera_id, "", "Camera ID in format YY-NN-- year and number.");
+DEFINE_string(channel, "/camera", "Camera channel to use");
+DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
+DEFINE_string(cpu_name, "", "Pi/Orin name to calibrate.");
+DEFINE_bool(display_undistorted, false,
+ "If true, display the undistorted image.");
namespace frc971::vision {
namespace {
@@ -32,7 +34,7 @@
aos::ShmEventLoop event_loop(&config.message());
- std::string hostname = FLAGS_pi;
+ std::string hostname = FLAGS_cpu_name;
if (hostname == "") {
hostname = aos::network::GetHostname();
LOG(INFO) << "Using pi/orin name from hostname as " << hostname;
@@ -41,9 +43,10 @@
<< "Need a base intrinsics json to use to auto-capture images when the "
"camera moves.";
std::unique_ptr<aos::ExitHandle> exit_handle = event_loop.MakeExitHandle();
- IntrinsicsCalibration extractor(
- &event_loop, hostname, FLAGS_camera_id, FLAGS_base_intrinsics,
- FLAGS_display_undistorted, FLAGS_calibration_folder, exit_handle.get());
+ IntrinsicsCalibration extractor(&event_loop, hostname, FLAGS_channel,
+ FLAGS_camera_id, FLAGS_base_intrinsics,
+ FLAGS_display_undistorted,
+ FLAGS_calibration_folder, exit_handle.get());
event_loop.Run();
diff --git a/frc971/vision/intrinsics_calibration_lib.cc b/frc971/vision/intrinsics_calibration_lib.cc
index a5ffec7..6f242f4 100644
--- a/frc971/vision/intrinsics_calibration_lib.cc
+++ b/frc971/vision/intrinsics_calibration_lib.cc
@@ -1,15 +1,23 @@
#include "frc971/vision/intrinsics_calibration_lib.h"
+DECLARE_bool(visualize);
+
namespace frc971::vision {
+// Found that under 50 ms would fail image too often on intrinsics with
+// visualize on
+constexpr aos::monotonic_clock::duration kMaxImageAge =
+ aos::monotonic_clock::duration(std::chrono::milliseconds(50));
+
IntrinsicsCalibration::IntrinsicsCalibration(
aos::EventLoop *event_loop, std::string_view hostname,
- std::string_view camera_id, std::string_view base_intrinsics_file,
- bool display_undistorted, std::string_view calibration_folder,
- aos::ExitHandle *exit_handle)
+ std::string_view camera_channel, std::string_view camera_id,
+ std::string_view base_intrinsics_file, bool display_undistorted,
+ std::string_view calibration_folder, aos::ExitHandle *exit_handle)
: hostname_(hostname),
cpu_type_(aos::network::ParsePiOrOrin(hostname_)),
cpu_number_(aos::network::ParsePiOrOrinNumber(hostname_)),
+ camera_channel_(camera_channel),
camera_id_(camera_id),
prev_H_camera_board_(Eigen::Affine3d()),
prev_image_H_camera_board_(Eigen::Affine3d()),
@@ -18,7 +26,7 @@
base_intrinsics_file)),
charuco_extractor_(
event_loop, &base_intrinsics_.message(), TargetType::kCharuco,
- "/camera",
+ camera_channel_,
[this](cv::Mat rgb_image, const aos::monotonic_clock::time_point eof,
std::vector<cv::Vec4i> charuco_ids,
std::vector<std::vector<cv::Point2f>> charuco_corners,
@@ -30,17 +38,18 @@
image_callback_(
event_loop,
absl::StrCat("/", aos::network::ParsePiOrOrin(hostname_).value(),
- // TODO: Need to make this work with multiple cameras
- std::to_string(cpu_number_.value()), "/camera"),
+ std::to_string(cpu_number_.value()), camera_channel_),
[this](cv::Mat rgb_image,
const aos::monotonic_clock::time_point eof) {
charuco_extractor_.HandleImage(rgb_image, eof);
},
- std::chrono::milliseconds(5)),
+ kMaxImageAge),
display_undistorted_(display_undistorted),
calibration_folder_(calibration_folder),
exit_handle_(exit_handle) {
- LOG(INFO) << "Hostname is: " << hostname_;
+ LOG(INFO) << "Hostname is: " << hostname_ << " and camera channel is "
+ << camera_channel_;
+
CHECK(cpu_number_) << ": Invalid cpu number " << hostname_
<< ", failed to parse cpu number";
std::regex re{"^[0-9][0-9]-[0-9][0-9]"};
@@ -54,25 +63,28 @@
std::vector<std::vector<cv::Point2f>> charuco_corners, bool valid,
std::vector<Eigen::Vector3d> rvecs_eigen,
std::vector<Eigen::Vector3d> tvecs_eigen) {
- // Reduce resolution displayed on remote viewer to prevent lag
- cv::resize(rgb_image, rgb_image,
- cv::Size(rgb_image.cols / 2, rgb_image.rows / 2));
- cv::imshow("Display", rgb_image);
+ if (FLAGS_visualize) {
+ // Reduce resolution displayed on remote viewer to prevent lag
+ cv::resize(rgb_image, rgb_image,
+ cv::Size(rgb_image.cols / 2, rgb_image.rows / 2));
+ cv::imshow("Display", rgb_image);
- if (display_undistorted_) {
- const cv::Size image_size(rgb_image.cols, rgb_image.rows);
- cv::Mat undistorted_rgb_image(image_size, CV_8UC3);
- cv::undistort(rgb_image, undistorted_rgb_image,
- charuco_extractor_.camera_matrix(),
- charuco_extractor_.dist_coeffs());
+ if (display_undistorted_) {
+ const cv::Size image_size(rgb_image.cols, rgb_image.rows);
+ cv::Mat undistorted_rgb_image(image_size, CV_8UC3);
+ cv::undistort(rgb_image, undistorted_rgb_image,
+ charuco_extractor_.camera_matrix(),
+ charuco_extractor_.dist_coeffs());
- cv::imshow("Display undist", undistorted_rgb_image);
+ cv::imshow("Display undist", undistorted_rgb_image);
+ }
}
int keystroke = cv::waitKey(1);
// If we haven't got a valid pose estimate, don't use these points
if (!valid) {
+ LOG(INFO) << "Skipping because pose is not valid";
return;
}
CHECK(tvecs_eigen.size() == 1)
@@ -99,8 +111,8 @@
bool store_image = false;
double percent_motion =
std::max<double>(r_norm / kDeltaRThreshold, t_norm / kDeltaTThreshold);
- LOG(INFO) << "Captured: " << all_charuco_ids_.size() << " points; Moved "
- << percent_motion << "% of what's needed";
+ LOG(INFO) << "Captured: " << all_charuco_ids_.size() << " points; \nMoved "
+ << static_cast<int>(percent_motion * 100) << "% of what's needed";
// Verify that camera has moved enough from last stored image
if (r_norm > kDeltaRThreshold || t_norm > kDeltaTThreshold) {
// frame_ refers to deltas between current and last captured image
@@ -120,9 +132,11 @@
double percent_stop = std::max<double>(frame_r_norm / kFrameDeltaRLimit,
frame_t_norm / kFrameDeltaTLimit);
LOG(INFO) << "Captured: " << all_charuco_ids_.size()
- << "points; Moved enough (" << percent_motion
- << "%); Need to stop (last motion was " << percent_stop
- << "% of limit; needs to be < 1 to capture)";
+ << "points; \nMoved enough ("
+ << static_cast<int>(percent_motion * 100)
+ << "%); Need to stop (last motion was "
+ << static_cast<int>(percent_stop * 100)
+ << "% of limit; needs to be < 1% to capture)";
}
prev_image_H_camera_board_ = H_camera_board_;
@@ -157,7 +171,8 @@
IntrinsicsCalibration::BuildCalibration(
cv::Mat camera_matrix, cv::Mat dist_coeffs,
aos::realtime_clock::time_point realtime_now, std::string_view cpu_type,
- int cpu_number, std::string_view camera_id, uint16_t team_number) {
+ uint16_t cpu_number, std::string_view camera_channel,
+ std::string_view camera_id, uint16_t team_number) {
flatbuffers::FlatBufferBuilder fbb;
flatbuffers::Offset<flatbuffers::String> name_offset =
fbb.CreateString(absl::StrFormat("%s%d", cpu_type, cpu_number));
@@ -169,6 +184,9 @@
reinterpret_cast<double *>(camera_matrix.data)[i]);
});
+ std::optional<uint16_t> camera_number =
+ frc971::vision::CameraNumberFromChannel(std::string(camera_channel));
+
flatbuffers::Offset<flatbuffers::Vector<float>>
distortion_coefficients_offset =
fbb.CreateVector<float>(5u, [&dist_coeffs](size_t i) {
@@ -180,6 +198,7 @@
camera_calibration_builder.add_node_name(name_offset);
camera_calibration_builder.add_team_number(team_number);
+ camera_calibration_builder.add_camera_number(camera_number.value());
camera_calibration_builder.add_camera_id(camera_id_offset);
camera_calibration_builder.add_calibration_timestamp(
realtime_now.time_since_epoch().count());
@@ -220,17 +239,25 @@
CHECK(team_number) << ": Invalid hostname " << hostname_
<< ", failed to parse team number";
aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
- camera_calibration = BuildCalibration(
- camera_matrix, dist_coeffs, realtime_now, cpu_type_.value(),
- cpu_number_.value(), camera_id_, team_number.value());
+ camera_calibration =
+ BuildCalibration(camera_matrix, dist_coeffs, realtime_now,
+ cpu_type_.value(), cpu_number_.value(),
+ camera_channel_, camera_id_, team_number.value());
std::stringstream time_ss;
time_ss << realtime_now;
+ std::string camera_number_optional = "";
+ std::optional<uint16_t> camera_number =
+ frc971::vision::CameraNumberFromChannel(camera_channel_);
+ if (camera_number != std::nullopt) {
+ camera_number_optional = "-" + std::to_string(camera_number.value());
+ }
const std::string calibration_filename =
calibration_folder_ +
- absl::StrFormat("/calibration_%s-%d-%d_cam-%s_%s.json",
+ absl::StrFormat("/calibration_%s-%d-%d%s_cam-%s_%s.json",
cpu_type_.value(), team_number.value(),
- cpu_number_.value(), camera_id_, time_ss.str());
+ cpu_number_.value(), camera_number_optional, camera_id_,
+ time_ss.str());
LOG(INFO) << calibration_filename << " -> "
<< aos::FlatbufferToJson(camera_calibration,
diff --git a/frc971/vision/intrinsics_calibration_lib.h b/frc971/vision/intrinsics_calibration_lib.h
index 7f08138..fda7ca4 100644
--- a/frc971/vision/intrinsics_calibration_lib.h
+++ b/frc971/vision/intrinsics_calibration_lib.h
@@ -15,12 +15,14 @@
#include "aos/time/time.h"
#include "aos/util/file.h"
#include "frc971/vision/charuco_lib.h"
+#include "frc971/vision/vision_util_lib.h"
namespace frc971::vision {
class IntrinsicsCalibration {
public:
IntrinsicsCalibration(aos::EventLoop *event_loop, std::string_view hostname,
+ std::string_view camera_channel,
std::string_view camera_id,
std::string_view base_intrinsics_file,
bool display_undistorted,
@@ -39,8 +41,9 @@
static aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
BuildCalibration(cv::Mat camera_matrix, cv::Mat dist_coeffs,
aos::realtime_clock::time_point realtime_now,
- std::string_view cpu_type, int cpu_number,
- std::string_view camera_id, uint16_t team_number);
+ std::string_view cpu_type, uint16_t cpu_number,
+ std::string_view camera_channel, std::string_view camera_id,
+ uint16_t team_number);
private:
static constexpr double kDeltaRThreshold = M_PI / 6.0;
@@ -52,6 +55,7 @@
std::string hostname_;
const std::optional<std::string_view> cpu_type_;
const std::optional<uint16_t> cpu_number_;
+ const std::string camera_channel_;
const std::string camera_id_;
std::vector<std::vector<int>> all_charuco_ids_;
diff --git a/frc971/vision/vision_util_lib.cc b/frc971/vision/vision_util_lib.cc
index b65e883..bfd6209 100644
--- a/frc971/vision/vision_util_lib.cc
+++ b/frc971/vision/vision_util_lib.cc
@@ -43,4 +43,19 @@
return result;
}
+std::optional<uint16_t> CameraNumberFromChannel(std::string camera_channel) {
+ if (camera_channel.find("/camera") == std::string::npos) {
+ return std::nullopt;
+ }
+ // If the string doesn't end in /camera#, return nullopt
+ uint16_t cam_len = std::string("/camera").length();
+ if (camera_channel.length() != camera_channel.find("/camera") + cam_len + 1) {
+ return std::nullopt;
+ }
+
+ uint16_t camera_number = std::stoi(
+ camera_channel.substr(camera_channel.find("/camera") + cam_len, 1));
+ return camera_number;
+}
+
} // namespace frc971::vision
diff --git a/frc971/vision/vision_util_lib.h b/frc971/vision/vision_util_lib.h
index 6fb32eb..8ce651c 100644
--- a/frc971/vision/vision_util_lib.h
+++ b/frc971/vision/vision_util_lib.h
@@ -7,16 +7,24 @@
#include "frc971/vision/calibration_generated.h"
+// Extract the CameraExtrinsics from a CameraCalibration struct
namespace frc971::vision {
std::optional<cv::Mat> CameraExtrinsics(
const frc971::vision::calibration::CameraCalibration *camera_calibration);
+// Extract the CameraIntrinsics from a CameraCalibration struct
cv::Mat CameraIntrinsics(
const frc971::vision::calibration::CameraCalibration *camera_calibration);
+// Extract the CameraDistCoeffs from a CameraCalibration struct
cv::Mat CameraDistCoeffs(
const frc971::vision::calibration::CameraCalibration *camera_calibration);
+// Get the camera number from a camera channel name, e.g., return 2 from
+// "/camera2". Returns nullopt if string doesn't start with "/camera" or does
+// not have a number
+std::optional<uint16_t> CameraNumberFromChannel(std::string camera_channel);
+
} // namespace frc971::vision
#endif // FRC971_VISION_VISION_UTIL_LIB_H_
diff --git a/frc971/vision/vision_util_lib_test.cc b/frc971/vision/vision_util_lib_test.cc
new file mode 100644
index 0000000..ff9c0a3
--- /dev/null
+++ b/frc971/vision/vision_util_lib_test.cc
@@ -0,0 +1,15 @@
+#include "frc971/vision/vision_util_lib.h"
+
+#include "gtest/gtest.h"
+
+namespace frc971::vision {
+// For now, just testing extracting camera number from channel name
+TEST(VisionUtilsTest, CameraNumberFromChannel) {
+ ASSERT_EQ(CameraNumberFromChannel("/camera0").value(), 0);
+ ASSERT_EQ(CameraNumberFromChannel("/camera1").value(), 1);
+ ASSERT_EQ(CameraNumberFromChannel("/camera"), std::nullopt);
+ ASSERT_EQ(CameraNumberFromChannel("/orin1/camera0").value(), 0);
+ ASSERT_EQ(CameraNumberFromChannel("/orin1/camera1").value(), 1);
+ ASSERT_EQ(CameraNumberFromChannel("/orin1"), std::nullopt);
+}
+} // namespace frc971::vision
diff --git a/y2024/y2024_orin_template.json b/y2024/y2024_orin_template.json
index 2bb2f46..9b165fc 100644
--- a/y2024/y2024_orin_template.json
+++ b/y2024/y2024_orin_template.json
@@ -110,18 +110,7 @@
"max_size": 208
},
{
- "name": "/orin{{ NUM }}/camera1",
- "type": "frc971.vision.CameraImage",
- "source_node": "orin{{ NUM }}",
- "channel_storage_duration": 1000000000,
- "frequency": 65,
- "max_size": 4752384,
- "num_readers": 6,
- "read_method": "PIN",
- "num_senders": 18
- },
- {
- "name": "/orin{{ NUM }}/camera2",
+ "name": "/orin{{ NUM }}/camera0",
"type": "frc971.vision.CameraImage",
"source_node": "orin{{ NUM }}",
"channel_storage_duration": 1000000000,
@@ -133,6 +122,17 @@
},
{
"name": "/orin{{ NUM }}/camera1",
+ "type": "frc971.vision.CameraImage",
+ "source_node": "orin{{ NUM }}",
+ "channel_storage_duration": 1000000000,
+ "frequency": 65,
+ "max_size": 4752384,
+ "num_readers": 6,
+ "read_method": "PIN",
+ "num_senders": 18
+ },
+ {
+ "name": "/orin{{ NUM }}/camera0",
"type": "foxglove.CompressedImage",
"source_node": "orin{{ NUM }}",
"channel_storage_duration": 1000000000,
@@ -140,7 +140,7 @@
"max_size": 622384
},
{
- "name": "/orin{{ NUM }}/camera2",
+ "name": "/orin{{ NUM }}/camera1",
"type": "foxglove.CompressedImage",
"source_node": "orin{{ NUM }}",
"channel_storage_duration": 1000000000,
@@ -148,6 +148,13 @@
"max_size": 622384
},
{
+ "name": "/orin{{ NUM }}/camera0",
+ "type": "foxglove.ImageAnnotations",
+ "source_node": "orin{{ NUM }}",
+ "frequency": 65,
+ "max_size": 50000
+ },
+ {
"name": "/orin{{ NUM }}/camera1",
"type": "foxglove.ImageAnnotations",
"source_node": "orin{{ NUM }}",
@@ -155,11 +162,27 @@
"max_size": 50000
},
{
- "name": "/orin{{ NUM }}/camera2",
- "type": "foxglove.ImageAnnotations",
+ "name": "/orin{{ NUM }}/camera0",
+ "type": "frc971.vision.TargetMap",
"source_node": "orin{{ NUM }}",
"frequency": 65,
- "max_size": 50000
+ "num_senders": 2,
+ "max_size": 1024,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "imu"
+ ],
+ "destination_nodes": [
+ {
+ "name": "imu",
+ "priority": 4,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "orin{{ NUM }}"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
},
{
"name": "/orin{{ NUM }}/camera1",
@@ -185,37 +208,14 @@
]
},
{
- "name": "/orin{{ NUM }}/camera2",
- "type": "frc971.vision.TargetMap",
- "source_node": "orin{{ NUM }}",
- "frequency": 65,
- "num_senders": 2,
- "max_size": 1024,
- "logger": "LOCAL_AND_REMOTE_LOGGER",
- "logger_nodes": [
- "imu"
- ],
- "destination_nodes": [
- {
- "name": "imu",
- "priority": 4,
- "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
- "timestamp_logger_nodes": [
- "orin{{ NUM }}"
- ],
- "time_to_live": 5000000
- }
- ]
- },
- {
- "name": "/orin{{ NUM }}/aos/remote_timestamps/imu/orin{{ NUM }}/camera1/frc971-vision-TargetMap",
+ "name": "/orin{{ NUM }}/aos/remote_timestamps/imu/orin{{ NUM }}/camera0/frc971-vision-TargetMap",
"type": "aos.message_bridge.RemoteMessage",
"frequency": 80,
"source_node": "orin{{ NUM }}",
"max_size": 208
},
{
- "name": "/orin{{ NUM }}/aos/remote_timestamps/imu/orin{{ NUM }}/camera2/frc971-vision-TargetMap",
+ "name": "/orin{{ NUM }}/aos/remote_timestamps/imu/orin{{ NUM }}/camera1/frc971-vision-TargetMap",
"type": "aos.message_bridge.RemoteMessage",
"frequency": 80,
"source_node": "orin{{ NUM }}",
@@ -296,22 +296,22 @@
]
},
{
- "name": "foxglove_image_converter1",
+ "name": "foxglove_image_converter0",
"executable_name": "foxglove_image_converter",
"user": "pi",
"args": [
- "--channel", "/camera1"
+ "--channel", "/camera0"
],
"nodes": [
"orin{{ NUM }}"
]
},
{
- "name": "foxglove_image_converter2",
+ "name": "foxglove_image_converter1",
"executable_name": "foxglove_image_converter",
"user": "pi",
"args": [
- "--channel", "/camera2"
+ "--channel", "/camera1"
],
"nodes": [
"orin{{ NUM }}"
@@ -326,11 +326,24 @@
]
},
{
- "name": "argus_camera1",
+ "name": "argus_camera0",
"executable_name": "argus_camera",
"args": [
"--enable_ftrace",
"--camera=0",
+ "--channel=/camera0",
+ ],
+ "user": "pi",
+ "nodes": [
+ "orin{{ NUM }}"
+ ]
+ },
+ {
+ "name": "argus_camera1",
+ "executable_name": "argus_camera",
+ "args": [
+ "--enable_ftrace",
+ "--camera=1",
"--channel=/camera1",
],
"user": "pi",
@@ -339,12 +352,10 @@
]
},
{
- "name": "argus_camera2",
- "executable_name": "argus_camera",
+ "name": "apriltag_detector0",
+ "executable_name": "apriltag_detector",
"args": [
- "--enable_ftrace",
- "--camera=1",
- "--channel=/camera2",
+ "--channel=/camera0",
],
"user": "pi",
"nodes": [
@@ -361,17 +372,6 @@
"nodes": [
"orin{{ NUM }}"
]
- },
- {
- "name": "apriltag_detector2",
- "executable_name": "apriltag_detector",
- "args": [
- "--channel=/camera2",
- ],
- "user": "pi",
- "nodes": [
- "orin{{ NUM }}"
- ]
}
],
"maps": [