2022-Robot
Robot code for 2022 FRC Season by Argos, FRC team #1756
Loading...
Searching...
No Matches
measure_up.h
Go to the documentation of this file.
1
4
5#pragma once
6
7#include <units/angle.h>
8#include <units/length.h>
9
10#include <array>
11
12#include <opencv2/calib3d.hpp>
13
14namespace measure_up {
15 constexpr auto intakeExtension = 18_cm;
16 constexpr auto bumperExtension = 3_in;
17 namespace chassis {
18 constexpr units::inch_t width{28.0};
19 constexpr units::inch_t length{31.0};
20 } // namespace chassis
21 namespace swerve_offsets {
22 constexpr auto frontLeftLOffset = 4.0_in;
23 constexpr auto frontLeftWOffset = 4.0_in;
24 constexpr auto frontRightLOffset = 4.0_in;
25 constexpr auto frontRightWOffset = 4.0_in;
26 constexpr auto backRightWOffset = 4.0_in;
27 constexpr auto backRightLOffset = 4.0_in;
28 constexpr auto backLeftWOffset = 4.0_in;
29 constexpr auto backLeftLOffset = 4.0_in;
30 } // namespace swerve_offsets
31 namespace hood {
32 namespace comp_bot {
33 constexpr auto homeAngle = 1.4_deg * -1;
34 } // namespace comp_bot
35 namespace practice_bot {
36 constexpr auto homeAngle = 1.2_deg * -1;
37 } // namespace practice_bot
38 } // namespace hood
39 namespace turret {
40 constexpr auto homeAngle = 180_deg;
41 constexpr auto minAngle = 30_deg;
42 constexpr auto maxAngle = 400_deg;
43 } // namespace turret
44 namespace camera {
45 // constexpr auto cameraHeight = 28.5_in; // Front camera
46 constexpr auto cameraHeight = 36.7_in; // Rear camera
47 constexpr auto upperHubHeight = 104_in;
48 constexpr auto cameraMountAngle = 27_deg; // actual current camera mount angle is 27.8 degrees
49 constexpr auto cameraMountAnglePracticeBot = 27.8_deg; // Rear camera
50 // constexpr auto toRotationCenter = 9_in; // Front camera
51 constexpr auto toRotationCenter = 7_in * -1; // Rear camera
52
53 // const float cameraIntrinsicValues[] =
54 static const cv::Matx33d intrinsics{2.5751292067328632e+02,
55 0.,
56 1.5971077914723165e+02,
57 0.,
58 2.5635071715912881e+02,
59 1.1971433393615548e+02,
60 0.,
61 0.,
62 1.};
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};
68 // const cv::Mat1f cameraIntrinsics(3, 3, &cameraIntrinsicValues[0]);
69
70 } // namespace camera
71 namespace climber_arm {
72 constexpr auto homeExtension = 21.5_in;
73 } // namespace climber_arm
74 namespace climber_hook {
75 constexpr auto homeExtension = 35.25_in;
76 constexpr auto maxExtension = 35.00_in;
77 constexpr auto minExtension = 1_in;
78 } // namespace climber_hook
79 namespace closepositions {
80 constexpr auto fixedLongDist = 21.5_in; //< Front and back distance from shooter to frame perimeter
81 constexpr auto fixedShortDist = 18.5_in; //< Left and right distance from shooter to frame perimeter
82 constexpr auto fixedFrontPos = 360_deg;
83 constexpr auto fixedLeftPos = 90_deg;
84 constexpr auto fixedBackPos = 180_deg;
85 constexpr auto fixedRightPos = 270_deg;
86 } // namespace closepositions
87} // namespace measure_up
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