Daedalus (PY2026)
Codebase for the Husky Robotics 2025-2026 rover Daedalus
Loading...
Searching...
No Matches
Constants::Arm Namespace Reference

Arm constants. More...

Variables

const double SHOULDER_LENGTH = 0.6
 Length of the Shoulder link, in meters.
 
const double ELBOW_LENGTH = 0.7
 Length of the Elbow link, in meters.
 
const double SAFETY_FACTOR = 0.95
 Percentage of fully extended overall arm length to limit arm extension within.
 
const double MAX_EE_VEL = 0.1
 Maximum commanded end-effector velocity, in m/s.
 
const double IK_SOLVER_THRESH = 0.001
 
const int IK_SOLVER_MAX_ITER = 50
 
const std::array< robot::types::jointid_t, 2 > IK_MOTOR_JOINTS
 The joints corresponding to the motors used for IK in the arm.
 
const std::array< robot::types::motorid_t, 2 > IK_MOTORS
 The motors used in IK.
 
constexpr frozen::unordered_map< motorid_t, std::pair< int, int >, IK_MOTORS.size()> JOINT_LIMITS
 Map from motor ids to min and max joint limits in millidegrees.
 
constexpr frozen::unordered_map< motorid_t, double, IK_MOTORS.size()> SEGMENT_LENGTHS
 Map from motor ids to segment length in meters.
 

Detailed Description

Arm constants.

Variable Documentation

◆ IK_MOTOR_JOINTS

const std::array< jointid_t, 2 > Constants::Arm::IK_MOTOR_JOINTS
Initial value:
= {
robot::types::jointid_t::shoulder, robot::types::jointid_t::elbow}

The joints corresponding to the motors used for IK in the arm.

The ordering in this array is the canonical ordering of these joints for IK purposes.

◆ IK_MOTORS

const std::array< motorid_t, 2 > Constants::Arm::IK_MOTORS
Initial value:
= ([]() {
for (size_t i = 0; i < IK_MOTOR_JOINTS.size(); i++) {
}
return ret;
})()
const std::array< robot::types::jointid_t, 2 > IK_MOTOR_JOINTS
The joints corresponding to the motors used for IK in the arm.
Definition Constants.cpp:15
constexpr auto JOINT_MOTOR_MAP
A map that pairs each of the joints to its corresponding motor.
Definition Constants.h:229
motorid_t
The motors on the robot.
Definition data.h:57

The motors used in IK.

The i-th element in this array corresponds to the joint in the i-th element of IK_MOTOR_JOINTS

◆ JOINT_LIMITS

frozen::unordered_map<motorid_t, std::pair<int, int>, IK_MOTORS.size()> Constants::Arm::JOINT_LIMITS
constexpr
Initial value:
{
{motorid_t::shoulder, {18200, 152500}}, {motorid_t::elbow, {-169100, 0}}}

Map from motor ids to min and max joint limits in millidegrees.

◆ SEGMENT_LENGTHS

frozen::unordered_map<motorid_t, double, IK_MOTORS.size()> Constants::Arm::SEGMENT_LENGTHS
constexpr
Initial value:
{
{motorid_t::shoulder, 0.3848608}, {motorid_t::elbow, 0.461264}}

Map from motor ids to segment length in meters.