mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[robotpy] Mirror most other subprojects (#8208)
GitOrigin-RevId: ac60fd3cf4a24023184376687da28373d14b781a This mirrors the robotpy files for the following projects: - apriltag - datalog - hal - ntcore - romiVendordep - wpilibc - wpimath - xrpVendordep This excludes cscore and the halsim wrappers for at this time. NOTE: This does not hook these projects up to the build system, just simply mirrors the files. The building will take place in a follow up PR to make it easier to review the changes necessary to build.
This commit is contained in:
4
apriltag/src/main/python/README.md
Normal file
4
apriltag/src/main/python/README.md
Normal file
@@ -0,0 +1,4 @@
|
||||
robotpy-apriltag
|
||||
================
|
||||
|
||||
RobotPy wrappers around WPILib's version of the apriltag library.
|
||||
41
apriltag/src/main/python/native-pyproject.toml
Normal file
41
apriltag/src/main/python/native-pyproject.toml
Normal file
@@ -0,0 +1,41 @@
|
||||
[build-system]
|
||||
build-backend = "hatchling.build"
|
||||
requires = [
|
||||
"hatchling",
|
||||
"hatch-nativelib~=0.2.0",
|
||||
"hatch-robotpy~=0.2.1",
|
||||
"robotpy-native-wpiutil==2027.0.0a2",
|
||||
"robotpy-native-wpimath==2027.0.0a2",
|
||||
]
|
||||
|
||||
[project]
|
||||
name = "robotpy-native-apriltag"
|
||||
version = "2027.0.0a2"
|
||||
description = "WPILib AprilTag Library"
|
||||
license = "BSD-3-Clause"
|
||||
|
||||
dependencies = [
|
||||
"robotpy-native-wpiutil==2027.0.0a2",
|
||||
"robotpy-native-wpimath==2027.0.0a2",
|
||||
]
|
||||
|
||||
[tool.hatch.build.targets.wheel]
|
||||
packages = ["src/native"]
|
||||
|
||||
[[tool.hatch.build.hooks.robotpy.maven_lib_download]]
|
||||
artifact_id = "apriltag-cpp"
|
||||
group_id = "edu.wpi.first.apriltag"
|
||||
repo_url = "https://frcmaven.wpi.edu/artifactory/release-2027"
|
||||
version = "2027.0.0-alpha-2"
|
||||
|
||||
extract_to = "src/native/apriltag"
|
||||
libs = ["apriltag"]
|
||||
|
||||
[[tool.hatch.build.hooks.nativelib.pcfile]]
|
||||
pcfile = "src/native/apriltag/robotpy-native-apriltag.pc"
|
||||
name = "apriltag"
|
||||
|
||||
includedir = "src/native/apriltag/include"
|
||||
libdir = "src/native/apriltag/lib"
|
||||
shared_libraries = ["apriltag"]
|
||||
requires = ["robotpy-native-wpiutil", "robotpy-native-wpimath"]
|
||||
74
apriltag/src/main/python/pyproject.toml
Normal file
74
apriltag/src/main/python/pyproject.toml
Normal file
@@ -0,0 +1,74 @@
|
||||
[build-system]
|
||||
build-backend = "hatchling.build"
|
||||
requires = [
|
||||
"semiwrap~=0.1.7",
|
||||
"hatch-meson~=0.1.0b2",
|
||||
"hatch-robotpy~=0.2.1",
|
||||
"hatchling",
|
||||
"robotpy-native-apriltag==2027.0.0a2",
|
||||
"robotpy-wpiutil==2027.0.0a2",
|
||||
"robotpy-wpimath==2027.0.0a2",
|
||||
]
|
||||
|
||||
[project]
|
||||
name = "robotpy-apriltag"
|
||||
version = "2027.0.0a2"
|
||||
description = "RobotPy bindings for WPILib's AprilTag library"
|
||||
authors = [
|
||||
{name = "RobotPy Development Team", email = "robotpy@googlegroups.com"},
|
||||
]
|
||||
license = "BSD-3-Clause"
|
||||
dependencies = [
|
||||
"robotpy-native-apriltag==2027.0.0a2",
|
||||
"robotpy-wpiutil==2027.0.0a2",
|
||||
"robotpy-wpimath==2027.0.0a2",
|
||||
]
|
||||
|
||||
[project.urls]
|
||||
"Source code" = "https://github.com/robotpy/mostrobotpy"
|
||||
|
||||
|
||||
[tool.hatch.build.hooks.robotpy]
|
||||
version_file = "robotpy_apriltag/version.py"
|
||||
|
||||
[tool.hatch.build.hooks.semiwrap]
|
||||
|
||||
[tool.hatch.build.hooks.meson]
|
||||
|
||||
[tool.hatch.build.targets.wheel]
|
||||
packages = ["robotpy_apriltag"]
|
||||
|
||||
|
||||
[tool.semiwrap]
|
||||
update_init = [
|
||||
"robotpy_apriltag robotpy_apriltag._apriltag"
|
||||
]
|
||||
scan_headers_ignore = [
|
||||
"common/*",
|
||||
"test/*",
|
||||
|
||||
"apriltag.h",
|
||||
"apriltag_math.h",
|
||||
"apriltag_pose.h",
|
||||
|
||||
"frc/apriltag/AprilTagDetector_cv.h",
|
||||
|
||||
"tag16h5.h",
|
||||
"tag36h11.h",
|
||||
]
|
||||
|
||||
[tool.semiwrap.extension_modules."robotpy_apriltag._apriltag"]
|
||||
name = "apriltag"
|
||||
wraps = ["robotpy-native-apriltag"]
|
||||
depends = ["wpiutil", "wpimath"]
|
||||
|
||||
[tool.semiwrap.extension_modules."robotpy_apriltag._apriltag".headers]
|
||||
# frc/apriltag
|
||||
AprilTag = "frc/apriltag/AprilTag.h"
|
||||
AprilTagDetection = "frc/apriltag/AprilTagDetection.h"
|
||||
AprilTagDetector = "frc/apriltag/AprilTagDetector.h"
|
||||
# AprilTagDetector_cv = "frc/apriltag/AprilTagDetector_cv.h"
|
||||
AprilTagFieldLayout = "frc/apriltag/AprilTagFieldLayout.h"
|
||||
AprilTagFields = "frc/apriltag/AprilTagFields.h"
|
||||
AprilTagPoseEstimate = "frc/apriltag/AprilTagPoseEstimate.h"
|
||||
AprilTagPoseEstimator = "frc/apriltag/AprilTagPoseEstimator.h"
|
||||
22
apriltag/src/main/python/robotpy_apriltag/__init__.py
Normal file
22
apriltag/src/main/python/robotpy_apriltag/__init__.py
Normal file
@@ -0,0 +1,22 @@
|
||||
from . import _init__apriltag
|
||||
|
||||
# autogenerated by 'semiwrap create-imports robotpy_apriltag robotpy_apriltag._apriltag'
|
||||
from ._apriltag import (
|
||||
AprilTag,
|
||||
AprilTagDetection,
|
||||
AprilTagDetector,
|
||||
AprilTagField,
|
||||
AprilTagFieldLayout,
|
||||
AprilTagPoseEstimate,
|
||||
AprilTagPoseEstimator,
|
||||
)
|
||||
|
||||
__all__ = [
|
||||
"AprilTag",
|
||||
"AprilTagDetection",
|
||||
"AprilTagDetector",
|
||||
"AprilTagField",
|
||||
"AprilTagFieldLayout",
|
||||
"AprilTagPoseEstimate",
|
||||
"AprilTagPoseEstimator",
|
||||
]
|
||||
0
apriltag/src/main/python/robotpy_apriltag/py.typed
Normal file
0
apriltag/src/main/python/robotpy_apriltag/py.typed
Normal file
4
apriltag/src/main/python/robotpy_apriltag/src/main.cpp
Normal file
4
apriltag/src/main/python/robotpy_apriltag/src/main.cpp
Normal file
@@ -0,0 +1,4 @@
|
||||
|
||||
#include "semiwrap_init.robotpy_apriltag._apriltag.hpp"
|
||||
|
||||
SEMIWRAP_PYBIND11_MODULE(m) { initWrapper(m); }
|
||||
16
apriltag/src/main/python/semiwrap/AprilTag.yml
Normal file
16
apriltag/src/main/python/semiwrap/AprilTag.yml
Normal file
@@ -0,0 +1,16 @@
|
||||
functions:
|
||||
to_json:
|
||||
ignore: true
|
||||
from_json:
|
||||
ignore: true
|
||||
classes:
|
||||
frc::AprilTag:
|
||||
attributes:
|
||||
ID:
|
||||
pose:
|
||||
methods:
|
||||
Generate36h11AprilTagImage:
|
||||
ignore: true
|
||||
Generate16h5AprilTagImage:
|
||||
ignore: true
|
||||
operator==:
|
||||
43
apriltag/src/main/python/semiwrap/AprilTagDetection.yml
Normal file
43
apriltag/src/main/python/semiwrap/AprilTagDetection.yml
Normal file
@@ -0,0 +1,43 @@
|
||||
extra_includes:
|
||||
- pybind11/eigen.h
|
||||
|
||||
classes:
|
||||
frc::AprilTagDetection:
|
||||
methods:
|
||||
GetFamily:
|
||||
GetId:
|
||||
GetHamming:
|
||||
GetDecisionMargin:
|
||||
GetHomography:
|
||||
GetHomographyMatrix:
|
||||
GetCenter:
|
||||
GetCorner:
|
||||
GetCorners:
|
||||
inline_code: |
|
||||
.def("__repr__", [](const AprilTagDetection &self) {
|
||||
return py::str("<AprilTagDetection tag_family={} tag_id={} hamming={} decision_margin={} center={}>")
|
||||
.format(self.GetFamily(), self.GetId(), self.GetHamming(), self.GetDecisionMargin(), self.GetCenter());
|
||||
})
|
||||
frc::AprilTagDetection::Point:
|
||||
attributes:
|
||||
x:
|
||||
y:
|
||||
inline_code: |
|
||||
.def(py::init([](double x, double y) {
|
||||
AprilTagDetection::Point pt{x, y};
|
||||
return std::make_unique<AprilTagDetection::Point>(std::move(pt));
|
||||
}), py::arg("x"), py::arg("y"))
|
||||
.def("__len__", [](const AprilTagDetection::Point &self) { return 2; })
|
||||
.def("__getitem__", [](const AprilTagDetection::Point &self, int index) {
|
||||
switch (index) {
|
||||
case 0:
|
||||
return self.x;
|
||||
case 1:
|
||||
return self.y;
|
||||
default:
|
||||
throw std::out_of_range("AprilTagDetection.Point index out of range");
|
||||
}
|
||||
})
|
||||
.def("__repr__", [](const AprilTagDetection::Point &self) {
|
||||
return py::str("AprilTagDetection.Point(x={}, y={})").format(self.x, self.y);
|
||||
})
|
||||
99
apriltag/src/main/python/semiwrap/AprilTagDetector.yml
Normal file
99
apriltag/src/main/python/semiwrap/AprilTagDetector.yml
Normal file
@@ -0,0 +1,99 @@
|
||||
extra_includes:
|
||||
- pybind11_typing.h
|
||||
|
||||
classes:
|
||||
frc::AprilTagDetector:
|
||||
methods:
|
||||
AprilTagDetector:
|
||||
SetConfig:
|
||||
GetConfig:
|
||||
SetQuadThresholdParameters:
|
||||
GetQuadThresholdParameters:
|
||||
AddFamily:
|
||||
RemoveFamily:
|
||||
ClearFamilies:
|
||||
Detect:
|
||||
overloads:
|
||||
int, int, int, uint8_t*:
|
||||
ignore: true
|
||||
int, int, uint8_t*:
|
||||
ignore: true
|
||||
inline_code: |
|
||||
.def("detect", [](AprilTagDetector *self, py::buffer img) {
|
||||
|
||||
// validate the input image buffer
|
||||
auto buf = img.request();
|
||||
if (buf.ndim != 2) {
|
||||
throw py::value_error("buffer must only have two dimensions");
|
||||
} else if (buf.itemsize != 1) {
|
||||
throw py::value_error("buffer elements must be bytes");
|
||||
}
|
||||
|
||||
// We are going to move the detection result into this shared_ptr
|
||||
// so that python can keep it alive. We don't expose the result directly
|
||||
// to the user because we'd have to pretend it's a list, and that would
|
||||
// be annoying.
|
||||
std::shared_ptr<AprilTagDetector::Results> c_result;
|
||||
{
|
||||
py::gil_scoped_release unlock;
|
||||
c_result = std::make_shared<AprilTagDetector::Results>(std::move(self->Detect(buf.shape[1], buf.shape[0], (uint8_t*)buf.ptr)));
|
||||
}
|
||||
|
||||
// This tells python about the shared_ptr, and it'll keep it alive as
|
||||
// long as the python reference is alive. When we call get(), we marked
|
||||
// the return value as reference_internal so python will keep the python
|
||||
// reference for the results object alive for as long as all of its
|
||||
// results that we put into the list are alive
|
||||
py::object py_result = py::cast(c_result);
|
||||
auto len = c_result->size();
|
||||
auto get = py_result.attr("get");
|
||||
py::typing::List<AprilTagDetection> l(len);
|
||||
for (size_t i = 0; i < len; i++) {
|
||||
l[i] = get(i);
|
||||
}
|
||||
return l;
|
||||
}, py::arg("image"),
|
||||
R"doc(
|
||||
Detect tags from an 8-bit grayscale image with shape (height, width)
|
||||
|
||||
:return: list of results
|
||||
)doc"
|
||||
)
|
||||
frc::AprilTagDetector::Config:
|
||||
attributes:
|
||||
numThreads:
|
||||
quadDecimate:
|
||||
quadSigma:
|
||||
refineEdges:
|
||||
decodeSharpening:
|
||||
debug:
|
||||
methods:
|
||||
operator==:
|
||||
frc::AprilTagDetector::QuadThresholdParameters:
|
||||
attributes:
|
||||
minClusterPixels:
|
||||
maxNumMaxima:
|
||||
criticalAngle:
|
||||
maxLineFitMSE:
|
||||
minWhiteBlackDiff:
|
||||
deglitch:
|
||||
methods:
|
||||
operator==:
|
||||
frc::AprilTagDetector::Results:
|
||||
rename: _Results
|
||||
ignored_bases:
|
||||
- std::span<const AprilTagDetection* const>
|
||||
force_no_trampoline: true
|
||||
methods:
|
||||
Results:
|
||||
overloads:
|
||||
'':
|
||||
ignore: true
|
||||
void*, const private_init&:
|
||||
ignore: true
|
||||
inline_code: |
|
||||
// use the keepalive to keep the array of results around until
|
||||
// the user deletes them
|
||||
.def("get", [](const AprilTagDetector::Results &self, int i) {
|
||||
return self[i];
|
||||
}, py::return_value_policy::reference_internal)
|
||||
29
apriltag/src/main/python/semiwrap/AprilTagFieldLayout.yml
Normal file
29
apriltag/src/main/python/semiwrap/AprilTagFieldLayout.yml
Normal file
@@ -0,0 +1,29 @@
|
||||
functions:
|
||||
to_json:
|
||||
ignore: true
|
||||
from_json:
|
||||
ignore: true
|
||||
LoadAprilTagLayoutField:
|
||||
ignore: true
|
||||
classes:
|
||||
frc::AprilTagFieldLayout:
|
||||
enums:
|
||||
OriginPosition:
|
||||
methods:
|
||||
AprilTagFieldLayout:
|
||||
overloads:
|
||||
'':
|
||||
std::string_view:
|
||||
std::vector<AprilTag>, units::meter_t, units::meter_t:
|
||||
LoadField:
|
||||
GetFieldLength:
|
||||
GetFieldWidth:
|
||||
GetTags:
|
||||
SetOrigin:
|
||||
overloads:
|
||||
OriginPosition:
|
||||
const Pose3d&:
|
||||
GetOrigin:
|
||||
GetTagPose:
|
||||
Serialize:
|
||||
operator==:
|
||||
2
apriltag/src/main/python/semiwrap/AprilTagFields.yml
Normal file
2
apriltag/src/main/python/semiwrap/AprilTagFields.yml
Normal file
@@ -0,0 +1,2 @@
|
||||
enums:
|
||||
AprilTagField:
|
||||
@@ -0,0 +1,9 @@
|
||||
classes:
|
||||
frc::AprilTagPoseEstimate:
|
||||
attributes:
|
||||
pose1:
|
||||
pose2:
|
||||
error1:
|
||||
error2:
|
||||
methods:
|
||||
GetAmbiguity:
|
||||
36
apriltag/src/main/python/semiwrap/AprilTagPoseEstimator.yml
Normal file
36
apriltag/src/main/python/semiwrap/AprilTagPoseEstimator.yml
Normal file
@@ -0,0 +1,36 @@
|
||||
extra_includes:
|
||||
- frc/apriltag/AprilTagDetection.h
|
||||
|
||||
classes:
|
||||
frc::AprilTagPoseEstimator:
|
||||
methods:
|
||||
AprilTagPoseEstimator:
|
||||
SetConfig:
|
||||
GetConfig:
|
||||
EstimateHomography:
|
||||
overloads:
|
||||
const AprilTagDetection& [const]:
|
||||
std::span<const double, 9> [const]:
|
||||
EstimateOrthogonalIteration:
|
||||
overloads:
|
||||
const AprilTagDetection&, int [const]:
|
||||
std::span<const double, 9>, std::span<const double, 8>, int [const]:
|
||||
Estimate:
|
||||
overloads:
|
||||
const AprilTagDetection& [const]:
|
||||
std::span<const double, 9>, std::span<const double, 8> [const]:
|
||||
frc::AprilTagPoseEstimator::Config:
|
||||
force_no_default_constructor: true
|
||||
attributes:
|
||||
tagSize:
|
||||
fx:
|
||||
fy:
|
||||
cx:
|
||||
cy:
|
||||
methods:
|
||||
operator==:
|
||||
inline_code: |
|
||||
.def(py::init([](units::meter_t tagSize, double fx, double fy, double cx, double cy) {
|
||||
AprilTagPoseEstimator::Config cfg{tagSize, fx, fy, cx, cy};
|
||||
return std::make_unique<AprilTagPoseEstimator::Config>(std::move(cfg));
|
||||
}), py::arg("tagSize"), py::arg("fx"), py::arg("fy"), py::arg("cx"), py::arg("cy"))
|
||||
BIN
apriltag/src/test/python/tag1_640_480.jpg
Normal file
BIN
apriltag/src/test/python/tag1_640_480.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 26 KiB |
BIN
apriltag/src/test/python/tag2_16h5_straight.png
Normal file
BIN
apriltag/src/test/python/tag2_16h5_straight.png
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 9.8 KiB |
BIN
apriltag/src/test/python/tag2_45deg_X.png
Normal file
BIN
apriltag/src/test/python/tag2_45deg_X.png
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 12 KiB |
BIN
apriltag/src/test/python/tag2_45deg_y.png
Normal file
BIN
apriltag/src/test/python/tag2_45deg_y.png
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 11 KiB |
119
apriltag/src/test/python/test_detection.py
Normal file
119
apriltag/src/test/python/test_detection.py
Normal file
@@ -0,0 +1,119 @@
|
||||
import cv2
|
||||
import robotpy_apriltag
|
||||
from wpimath.geometry import Transform3d
|
||||
|
||||
import math
|
||||
import pathlib
|
||||
import pytest
|
||||
|
||||
|
||||
def test_point():
|
||||
point = robotpy_apriltag.AprilTagDetection.Point()
|
||||
|
||||
x, y = point
|
||||
|
||||
assert x == 0
|
||||
assert y == 0
|
||||
|
||||
|
||||
def _load_grayscale_image(fname):
|
||||
full_path = pathlib.Path(__file__).parent / fname
|
||||
img = cv2.imread(str(full_path))
|
||||
return cv2.cvtColor(img, cv2.COLOR_BGR2GRAY)
|
||||
|
||||
|
||||
def test_1():
|
||||
detector = robotpy_apriltag.AprilTagDetector()
|
||||
assert detector.addFamily("tag16h5")
|
||||
assert detector.addFamily("tag36h11")
|
||||
|
||||
img = _load_grayscale_image("tag1_640_480.jpg")
|
||||
results = detector.detect(img)
|
||||
|
||||
assert len(results) == 1
|
||||
assert results[0].getFamily() == "tag36h11"
|
||||
assert results[0].getId() == 1
|
||||
assert results[0].getHamming() == 0
|
||||
|
||||
estimator = robotpy_apriltag.AprilTagPoseEstimator(
|
||||
robotpy_apriltag.AprilTagPoseEstimator.Config(0.2, 500, 500, 320, 240)
|
||||
)
|
||||
|
||||
est = estimator.estimateOrthogonalIteration(results[0], 50)
|
||||
assert est.pose2 == Transform3d()
|
||||
pose = estimator.estimate(results[0])
|
||||
assert est.pose1 == pose
|
||||
|
||||
|
||||
def test_pose_rotated_x():
|
||||
"""
|
||||
This tag is rotated such that the top is closer to the camera than the bottom. In the camera
|
||||
frame, with +x to the right, this is a rotation about +X by 45 degrees.
|
||||
"""
|
||||
|
||||
detector = robotpy_apriltag.AprilTagDetector()
|
||||
assert detector.addFamily("tag16h5")
|
||||
|
||||
img = _load_grayscale_image("tag2_45deg_X.png")
|
||||
results = detector.detect(img)
|
||||
|
||||
assert len(results) == 1
|
||||
|
||||
estimator = robotpy_apriltag.AprilTagPoseEstimator(
|
||||
robotpy_apriltag.AprilTagPoseEstimator.Config(
|
||||
0.2, 500, 500, img.shape[1] / 2.0, img.shape[0] / 2.0
|
||||
)
|
||||
)
|
||||
est = estimator.estimateOrthogonalIteration(results[0], 50)
|
||||
assert pytest.approx(est.pose1.rotation().x, abs=0.1) == math.radians(45)
|
||||
assert pytest.approx(est.pose1.rotation().y, abs=0.1) == math.radians(0)
|
||||
assert pytest.approx(est.pose1.rotation().z, abs=0.1) == math.radians(0)
|
||||
|
||||
|
||||
def test_pose_rotated_y():
|
||||
"""
|
||||
This tag is rotated such that the right is closer to the camera than the left. In the camera
|
||||
frame, with +y down, this is a rotation of 45 degrees about +y.
|
||||
"""
|
||||
|
||||
detector = robotpy_apriltag.AprilTagDetector()
|
||||
assert detector.addFamily("tag16h5")
|
||||
|
||||
img = _load_grayscale_image("tag2_45deg_y.png")
|
||||
results = detector.detect(img)
|
||||
|
||||
assert len(results) == 1
|
||||
|
||||
estimator = robotpy_apriltag.AprilTagPoseEstimator(
|
||||
robotpy_apriltag.AprilTagPoseEstimator.Config(
|
||||
0.2, 500, 500, img.shape[1] / 2.0, img.shape[0] / 2.0
|
||||
)
|
||||
)
|
||||
est = estimator.estimateOrthogonalIteration(results[0], 50)
|
||||
assert pytest.approx(est.pose1.rotation().x, abs=0.1) == math.radians(0)
|
||||
assert pytest.approx(est.pose1.rotation().y, abs=0.1) == math.radians(45)
|
||||
assert pytest.approx(est.pose1.rotation().z, abs=0.1) == math.radians(0)
|
||||
|
||||
|
||||
def test_pose_straight_on():
|
||||
"""
|
||||
This tag is facing right at the camera -- no rotation should be observed.
|
||||
"""
|
||||
|
||||
detector = robotpy_apriltag.AprilTagDetector()
|
||||
assert detector.addFamily("tag16h5")
|
||||
|
||||
img = _load_grayscale_image("tag2_16h5_straight.png")
|
||||
results = detector.detect(img)
|
||||
|
||||
assert len(results) == 1
|
||||
|
||||
estimator = robotpy_apriltag.AprilTagPoseEstimator(
|
||||
robotpy_apriltag.AprilTagPoseEstimator.Config(
|
||||
0.2, 500, 500, img.shape[1] / 2.0, img.shape[0] / 2.0
|
||||
)
|
||||
)
|
||||
est = estimator.estimateOrthogonalIteration(results[0], 50)
|
||||
assert pytest.approx(est.pose1.rotation().x, abs=0.1) == math.radians(0)
|
||||
assert pytest.approx(est.pose1.rotation().y, abs=0.1) == math.radians(0)
|
||||
assert pytest.approx(est.pose1.rotation().z, abs=0.1) == math.radians(0)
|
||||
Reference in New Issue
Block a user