7#include <units/angle.h>
8#include <units/length.h>
12#include <opencv2/calib3d.hpp>
18 constexpr units::inch_t
width{28.0};
19 constexpr units::inch_t
length{31.0};
21 namespace swerve_offsets {
35 namespace practice_bot {
54 static const cv::Matx33d
intrinsics{2.5751292067328632e+02,
56 1.5971077914723165e+02,
58 2.5635071715912881e+02,
59 1.1971433393615548e+02,
63 static const cv::Matx<double, 1, 5>
distortion{2.9684613693070039e-01,
64 -1.4380252254747885e+00,
65 -2.2098421479494509e-03,
66 -3.3894563533907176e-03,
67 2.5344430354806740e+00};
71 namespace climber_arm {
74 namespace climber_hook {
79 namespace closepositions {
Definition: Constants.h:71
constexpr auto upperHubHeight
Definition: measure_up.h:47
constexpr auto toRotationCenter
Definition: measure_up.h:51
constexpr auto cameraMountAnglePracticeBot
Definition: measure_up.h:49
constexpr auto cameraMountAngle
Definition: measure_up.h:48
static const cv::Matx< double, 1, 5 > distortion
Definition: measure_up.h:63
static const cv::Matx33d intrinsics
Definition: measure_up.h:54
constexpr auto cameraHeight
Definition: measure_up.h:46
constexpr units::inch_t length
Definition: measure_up.h:19
constexpr units::inch_t width
Definition: measure_up.h:18
constexpr auto homeExtension
Length between mount points.
Definition: measure_up.h:72
constexpr auto maxExtension
Definition: measure_up.h:76
constexpr auto minExtension
Definition: measure_up.h:77
constexpr auto homeExtension
Length from arm pivot to inner edge of hook slider.
Definition: measure_up.h:75
constexpr auto fixedLongDist
Definition: measure_up.h:80
constexpr auto fixedRightPos
Definition: measure_up.h:85
constexpr auto fixedFrontPos
Definition: measure_up.h:82
constexpr auto fixedBackPos
Definition: measure_up.h:84
constexpr auto fixedShortDist
Definition: measure_up.h:81
constexpr auto fixedLeftPos
Definition: measure_up.h:83
constexpr auto homeAngle
Definition: measure_up.h:33
constexpr auto homeAngle
Definition: measure_up.h:36
constexpr auto backLeftLOffset
Definition: measure_up.h:29
constexpr auto frontRightWOffset
Definition: measure_up.h:25
constexpr auto frontLeftWOffset
Definition: measure_up.h:23
constexpr auto backRightWOffset
Definition: measure_up.h:26
constexpr auto backRightLOffset
Definition: measure_up.h:27
constexpr auto frontLeftLOffset
Definition: measure_up.h:22
constexpr auto frontRightLOffset
Definition: measure_up.h:24
constexpr auto backLeftWOffset
Definition: measure_up.h:28
constexpr auto maxAngle
Definition: measure_up.h:42
constexpr auto homeAngle
Definition: measure_up.h:40
constexpr auto minAngle
Definition: measure_up.h:41
Definition: measure_up.h:14
constexpr auto intakeExtension
Distance from frame to center of intake in x direction.
Definition: measure_up.h:15
constexpr auto bumperExtension
Distance from frame to outer edge of bumpers.
Definition: measure_up.h:16