diff --git a/src/CAN/CANMotor.cpp b/src/CAN/CANMotor.cpp index a68eda07..3e435575 100644 --- a/src/CAN/CANMotor.cpp +++ b/src/CAN/CANMotor.cpp @@ -92,6 +92,13 @@ void setMotorPIDConstants(deviceserial_t serial, int32_t kP, int32_t kI, int32_t std::this_thread::sleep_for(1ms); } +void setMotorPIDMaxPower(deviceserial_t serial, uint16_t maxPower) { + CANPacket p; + auto motorGroupCode = static_cast(devicegroup_t::motor); + AssembleMaxPIDPWMPacket(&p, motorGroupCode, serial, maxPower); + sendCANPacket(p); +} + void setMotorMode(deviceserial_t serial, motormode_t mode) { CANPacket p; AssembleModeSetPacket(&p, static_cast(devicegroup_t::motor), serial, diff --git a/src/CAN/CANMotor.h b/src/CAN/CANMotor.h index 7c092227..3e5f0213 100644 --- a/src/CAN/CANMotor.h +++ b/src/CAN/CANMotor.h @@ -136,6 +136,8 @@ void setMotorPower(deviceserial_t serial, int16_t power); */ void setMotorPIDTarget(deviceserial_t serial, int32_t target); +void setMotorPIDMaxPower(deviceserial_t serial, uint16_t maxPower); + /** * @brief Set the angle of the PCA servo * diff --git a/src/Constants.h b/src/Constants.h index b452cadf..cbcfecf8 100644 --- a/src/Constants.h +++ b/src/Constants.h @@ -183,8 +183,8 @@ constexpr frozen::unordered_map, IK * Map from motor ids to segment length in meters */ constexpr frozen::unordered_map - SEGMENT_LENGTHS{{robot::types::motorid_t::shoulder, 0.3848608}, - {robot::types::motorid_t::elbow, 0.461264}}; + SEGMENT_LENGTHS{{robot::types::motorid_t::shoulder, 0.394}, + {robot::types::motorid_t::elbow, 0.749}}; } // namespace arm namespace autonomous { diff --git a/src/TunePID.cpp b/src/TunePID.cpp index 9f6675d3..78792dad 100644 --- a/src/TunePID.cpp +++ b/src/TunePID.cpp @@ -18,7 +18,8 @@ extern "C" { } enum class targetmode_t { - step, sinusoidal + step, + sinusoidal }; using namespace robot::types; @@ -76,8 +77,11 @@ bool initMotor(motorid_t motor) { robot::encparams_t enc_params = robot::encMotors.at(motor); can::motor::initEncoder(serial, enc_params.isInverted, true, enc_params.ppjr, robot::TELEM_PERIOD); - can::motor::setLimitSwitchLimits(serial, enc_params.limitSwitchLow, - enc_params.limitSwitchHigh); + auto mDegToPulses = [&](int32_t mdeg) { + return static_cast((double)mdeg / 360000.0 * enc_params.ppjr); + }; + can::motor::setLimitSwitchLimits(serial, mDegToPulses(enc_params.limitSwitchLow), + mDegToPulses(enc_params.limitSwitchHigh)); } else { std::cerr << "The given motor is not a pot or enc motor!\n"; return false; @@ -132,13 +136,14 @@ int main(int argc, char** argv) { std::getline(std::cin, str); int d_coeff = std::stoi(str); - can::motor::setMotorMode(serial, can::motor::motormode_t::pid); can::motor::setMotorPIDConstants(serial, p_coeff, i_coeff, d_coeff); + can::motor::setMotorPIDMaxPower(serial, 32767); + can::motor::setMotorMode(serial, can::motor::motormode_t::pid); double period = 8.0; std::this_thread::sleep_for(300ms); // wait for encoder position data to arrive - int32_t starting_angle = can::motor::getMotorPosition(serial); + int32_t starting_angle = can::motor::getMotorPosition(serial).getData(); int32_t angle_target = starting_angle; double acc_error = 0.0; int total_steps = 0; @@ -159,7 +164,7 @@ int main(int argc, char** argv) { if (mode == targetmode_t::step) { prescaled_target = round(prescaled_target); } - angle_target = (int32_t) round(amplitude * prescaled_target) + starting_angle; + angle_target = (int32_t)round(amplitude * prescaled_target) + starting_angle; can::motor::setMotorPIDTarget(serial, angle_target); diff --git a/src/control/PlanarArmController.h b/src/control/PlanarArmController.h index 9ad79f65..41228864 100644 --- a/src/control/PlanarArmController.h +++ b/src/control/PlanarArmController.h @@ -210,12 +210,15 @@ class PlanarArmController { */ navtypes::Vectord getCommand(robot::types::datatime_t currTime, const navtypes::Vectord& currJointPos) { + LOG_SCOPE_F(INFO, "IK getCommand"); Eigen::Vector2d newPos = get_setpoint(currTime); // lock after calling get_setpoint since that internally locks the mutex std::lock_guard lock(mutex); // get new joint positions for target EE bool success = false; + LOG_F(INFO, "newPos=[%.2f, %.2f]", newPos(0), newPos(1)); + LOG_F(INFO, "currJP=[%.2f, %.2f]", currJointPos(0), currJointPos(1)); navtypes::Vectord jp = kin.eePosToJointPos(newPos, currJointPos, success); mutableFields->velTimestamp = currTime; if (!success) { diff --git a/src/world_interface/real_world_constants.h b/src/world_interface/real_world_constants.h index d17e621c..e8e06875 100644 --- a/src/world_interface/real_world_constants.h +++ b/src/world_interface/real_world_constants.h @@ -59,7 +59,7 @@ struct encparams_t { // clang-format off constexpr auto encMotors = frozen::make_unordered_map({ {motorid_t::shoulder, - {.isInverted = true, + {.isInverted = false, .ppjr = 4590 * 1024 * 4, .limitSwitchLow = Constants::arm::JOINT_LIMITS.at(robot::types::motorid_t::shoulder).first, .limitSwitchHigh = Constants::arm::JOINT_LIMITS.at(robot::types::motorid_t::shoulder).second, @@ -69,6 +69,7 @@ constexpr auto encMotors = frozen::make_unordered_map({ // TODO: find appropriate bounds constexpr auto potMotors = frozen::make_unordered_map({ + {motorid_t::elbow, {.adc_lo = 563, .mdeg_lo = -160000, .adc_hi = 1927, .mdeg_hi = 0}}, {motorid_t::forearm, {.adc_lo = 1208, .mdeg_lo = -180 * 1000, .adc_hi = 841, .mdeg_hi = 180 * 1000}}, {motorid_t::wristDiffLeft, @@ -107,7 +108,8 @@ constexpr auto motorSerialIDMap = frozen::make_unordered_map( - {{motorid_t::shoulder, {70, 0, 0}}, + {{motorid_t::shoulder, {200, 0, 0}}, + {motorid_t::elbow, {250, 0, 0}}, {motorid_t::frontLeftSwerve, {2, 0, 0}}, {motorid_t::frontRightSwerve, {2, 0, 0}}, {motorid_t::rearLeftSwerve, {2, 0, 0}}, @@ -119,8 +121,8 @@ constexpr auto motorPIDMap = frozen::make_unordered_map( */ constexpr auto positive_pwm_scales = frozen::make_unordered_map({{motorid_t::armBase, -0.25}, - {motorid_t::shoulder, -1}, - {motorid_t::elbow, -1}, + {motorid_t::shoulder, 1}, + {motorid_t::elbow, 1}, {motorid_t::forearm, -0.2}, {motorid_t::wristDiffLeft, -0.30}, {motorid_t::wristDiffRight, -0.30}, @@ -141,8 +143,8 @@ constexpr auto positive_pwm_scales = */ constexpr auto negative_pwm_scales = frozen::make_unordered_map({{motorid_t::armBase, -0.25}, - {motorid_t::shoulder, -1}, - {motorid_t::elbow, -1}, + {motorid_t::shoulder, 1}, + {motorid_t::elbow, 1}, {motorid_t::forearm, -0.2}, {motorid_t::wristDiffLeft, -0.30}, {motorid_t::wristDiffRight, -0.30}, diff --git a/src/world_interface/real_world_interface.cpp b/src/world_interface/real_world_interface.cpp index c1d73c2b..c8d9c627 100644 --- a/src/world_interface/real_world_interface.cpp +++ b/src/world_interface/real_world_interface.cpp @@ -84,8 +84,12 @@ void initMotors() { can::motor::initEncoder(serial, enc_params.isInverted, true, enc_params.ppjr, TELEM_PERIOD); - can::motor::setLimitSwitchLimits(serial, enc_params.limitSwitchLow, - enc_params.limitSwitchHigh); + auto mDegToPulses = [&](int32_t mdeg) { + return static_cast((double)mdeg / 360000.0 * enc_params.ppjr); + }; + // inverted because of weirdness + can::motor::setLimitSwitchLimits(serial, mDegToPulses(-enc_params.limitSwitchLow), + mDegToPulses(-enc_params.limitSwitchHigh)); } for (const auto& pair : robot::motorPIDMap) {