1010
1111#include < frozen/unordered_map.h>
1212
13+ using robot::types::CameraID;
14+ using robot::types::jointid_t ;
15+ using robot::types::motorid_t ;
16+
1317namespace Constants {
1418// TODO: make sure these are still accurate with the new arm.
1519extern const double SHOULDER_LENGTH;
@@ -54,13 +58,13 @@ extern const double MAX_DTHETA;
5458// TODO: We need to recalibrate the camera, since we replaced it with a different one.
5559// TODO: rename cameras (in MC as well) as appropriate
5660extern const char * MAST_CAMERA_CONFIG_PATH;
57- extern const robot::types:: CameraID MAST_CAMERA_ID;
61+ extern const CameraID MAST_CAMERA_ID;
5862
5963extern const char * FOREARM_CAMERA_CONFIG_PATH;
60- extern const robot::types:: CameraID FOREARM_CAMERA_ID;
64+ extern const CameraID FOREARM_CAMERA_ID;
6165
6266extern const char * HAND_CAMERA_CONFIG_PATH;
63- extern const robot::types:: CameraID HAND_CAMERA_ID;
67+ extern const CameraID HAND_CAMERA_ID;
6468
6569extern const uint16_t WS_SERVER_PORT;
6670
@@ -104,14 +108,6 @@ extern const double LANDMARK_WAYPOINT_RADIUS;
104108extern const double EPS;
105109} // namespace Nav
106110
107- // Lidar
108- namespace Lidar {
109- extern const std::string RP_PATH;
110- extern const double MM_PER_M;
111- extern const uint32_t RPLIDAR_A1_BAUDRATE;
112- extern const uint32_t RPLIDAR_S1_BAUDRATE;
113- } // namespace Lidar
114-
115111// Video encoding
116112namespace video {
117113/* *
@@ -126,22 +122,21 @@ extern const int H264_RF_CONSTANT;
126122/* *
127123 * @brief Stream-specific RF constants.
128124 */
129- extern const std::unordered_map<robot::types:: CameraID, int > STREAM_RFS;
125+ extern const std::unordered_map<CameraID, int > STREAM_RFS;
130126} // namespace video
131127
132128/* *
133129 * A map that pairs each of the joints to its corresponding motor.
134130 * (one-to-one pairs only)
135131 */
136- constexpr auto JOINT_MOTOR_MAP =
137- frozen::make_unordered_map<robot::types::jointid_t , robot::types::motorid_t >(
138- {{robot::types::jointid_t ::armBase, robot::types::motorid_t ::armBase},
139- {robot::types::jointid_t ::shoulder, robot::types::motorid_t ::shoulder},
140- {robot::types::jointid_t ::elbow, robot::types::motorid_t ::elbow},
141- {robot::types::jointid_t ::forearm, robot::types::motorid_t ::forearm},
142- {robot::types::jointid_t ::hand, robot::types::motorid_t ::hand},
143- {robot::types::jointid_t ::activeSuspension,
144- robot::types::motorid_t ::activeSuspension}});
132+ constexpr auto JOINT_MOTOR_MAP = frozen::make_unordered_map<jointid_t , motorid_t >(
133+ {{jointid_t ::armBase, motorid_t ::armBase},
134+ {jointid_t ::shoulder, motorid_t ::shoulder},
135+ {jointid_t ::elbow, motorid_t ::elbow},
136+ {jointid_t ::forearm, motorid_t ::forearm},
137+ {jointid_t ::hand, motorid_t ::hand},
138+ {jointid_t ::drillActuator, motorid_t ::drillActuator},
139+ {jointid_t ::drillMotor, motorid_t ::drillMotor}});
145140
146141// Arm inverse kinematics
147142namespace arm {
@@ -162,27 +157,25 @@ extern const int IK_SOLVER_MAX_ITER;
162157 * The joints corresponding to the motors used for IK in the arm. The ordering in this array is
163158 * the canonical ordering of these joints for IK purposes.
164159 */
165- extern const std::array<robot::types:: jointid_t , 2 > IK_MOTOR_JOINTS;
160+ extern const std::array<jointid_t , 2 > IK_MOTOR_JOINTS;
166161
167162/* *
168163 * The motors used in IK. The i-th element in this array corresponds to the joint in the i-th
169164 * element of `IK_MOTOR_JOINTS`
170165 */
171- extern const std::array<robot::types:: motorid_t , 2 > IK_MOTORS;
166+ extern const std::array<motorid_t , 2 > IK_MOTORS;
172167
173168/* *
174169 * Map from motor ids to min and max joint limits in millidegrees
175170 */
176- constexpr frozen::unordered_map<robot::types::motorid_t , std::pair<int , int >, IK_MOTORS.size()>
177- JOINT_LIMITS{{robot::types::motorid_t ::shoulder, {18200 , 152500 }},
178- {robot::types::motorid_t ::elbow, {-169100 , 0 }}};
171+ constexpr frozen::unordered_map<motorid_t , std::pair<int , int >, IK_MOTORS.size()> JOINT_LIMITS{
172+ {motorid_t ::shoulder, {18200 , 152500 }}, {motorid_t ::elbow, {-169100 , 0 }}};
179173
180174/* *
181175 * Map from motor ids to segment length in meters
182176 */
183- constexpr frozen::unordered_map<robot::types::motorid_t , double , IK_MOTORS.size()>
184- SEGMENT_LENGTHS{{robot::types::motorid_t ::shoulder, 0.3848608 },
185- {robot::types::motorid_t ::elbow, 0.461264 }};
177+ constexpr frozen::unordered_map<motorid_t , double , IK_MOTORS.size()> SEGMENT_LENGTHS{
178+ {motorid_t ::shoulder, 0.3848608 }, {motorid_t ::elbow, 0.461264 }};
186179} // namespace arm
187180
188181namespace autonomous {
0 commit comments