From 4032d591b6457aefeacbadd3ee3919a01998a115 Mon Sep 17 00:00:00 2001 From: qhdwight Date: Wed, 17 Apr 2024 21:37:12 -0400 Subject: [PATCH 01/10] Cleanup arm translator a bit --- .../arm_translator_bridge/arm_translator.cpp | 71 +++++-------------- src/util/units/units_eigen.hpp | 31 ++++++++ 2 files changed, 47 insertions(+), 55 deletions(-) create mode 100644 src/util/units/units_eigen.hpp diff --git a/src/esw/arm_translator_bridge/arm_translator.cpp b/src/esw/arm_translator_bridge/arm_translator.cpp index 9dd1ce6a6..8d1b91924 100644 --- a/src/esw/arm_translator_bridge/arm_translator.cpp +++ b/src/esw/arm_translator_bridge/arm_translator.cpp @@ -1,56 +1,23 @@ #include "arm_translator.hpp" -#include #include -#include -#include - -namespace Eigen { - - template< - typename Rep1, typename Conversion1, typename MeterExp1, typename KilogramExp1, typename SecondExp1, typename RadianExp1, typename AmpereExp1, typename KelvinExp1, typename ByteExp1, typename TickExp1, - typename Rep2, typename Conversion2, typename MeterExp2, typename KilogramExp2, typename SecondExp2, typename RadianExp2, typename AmpereExp2, typename KelvinExp2, typename ByteExp2, typename TickExp2> - struct ScalarBinaryOpTraits< - mrover::Unit, - mrover::Unit, - internal::scalar_product_op< - mrover::Unit, - mrover::Unit>> { - using U1 = mrover::Unit; - using U2 = mrover::Unit; - using ReturnType = mrover::multiply; - }; - - template<> - struct ScalarBinaryOpTraits< - mrover::Dimensionless, - mrover::Dimensionless, - internal::scalar_product_op> { - using ReturnType = mrover::Dimensionless; - }; - - // template - // struct NumTraits> : NumTraits { - // using U = mrover::Unit; - // using Real = U; - // using NonInteger = U; - // using Nested = U; - // enum { - // IsComplex = 0, - // IsInteger = 0, - // IsSigned = 1, - // RequireInitialization = 1, - // ReadCost = 1, - // AddCost = 3, - // MulCost = 3, - // }; - // }; - -} // namespace Eigen +#include +#include +#include namespace mrover { + // Maps pitch and roll values to the DE0 and DE1 motors outputs + // For example when only pitching the motor, both controllers should be moving in the same direction + // When rolling, the controllers should move in opposite directions + auto static const PITCH_ROLL_TO_0_1 = (Matrix2{} << -1, -1, -1, 1).finished(); + Dimensionless static constexpr PITCH_ROLL_TO_01_SCALE{40}; + + // How often we send an adjust command to the DE motors + // This updates the quadrature motor source on the Moteus based on the absolute encoder readings + double static constexpr DE_OFFSET_TIMER_PERIOD = 1; + ArmTranslator::ArmTranslator(ros::NodeHandle& nh) { for (std::string const& hwName: mArmHWNames) { [[maybe_unused]] auto [_, was_inserted] = mAdjustClientsByArmHwNames.try_emplace(hwName, nh.serviceClient(std::format("{}_adjust", hwName))); @@ -67,11 +34,9 @@ namespace mrover { mPositionPub = std::make_unique(nh.advertise("arm_hw_position_cmd", 1)); mJointDataPub = std::make_unique(nh.advertise("arm_joint_data", 1)); - mDeOffsetTimer = nh.createTimer(ros::Duration{1}, &ArmTranslator::updateDeOffsets, this); + mDeOffsetTimer = nh.createTimer(ros::Duration{DE_OFFSET_TIMER_PERIOD}, &ArmTranslator::updateDeOffsets, this); } - auto static const PITCH_ROLL_TO_0_1 = (Matrix2{} << -1, -1, -1, 1).finished(); - auto findJointByName(std::vector const& names, std::string const& name) -> std::optional { auto it = std::ranges::find(names, name); return it == names.end() ? std::nullopt : std::make_optional(std::distance(names.begin(), it)); @@ -103,10 +68,6 @@ namespace mrover { mThrottlePub->publish(throttle); } - // constexpr Dimensionless PITCH_ROLL_TO_01_SCALE = 40; - // Matrix2 static const PITCH_ROLL_TO_01_SCALED = PITCH_ROLL_TO_0_1 * PITCH_ROLL_TO_01_SCALE; - // Note (Isabel) PITCH_ROLL_TO_01_SCALE is unnecessary, moteus config will scale for gear ratio - auto ArmTranslator::processVelocityCmd(Velocity::ConstPtr const& msg) -> void { if (msg->names.size() != msg->velocities.size()) { ROS_ERROR("Name count and value count mismatched!"); @@ -148,7 +109,7 @@ namespace mrover { std::size_t pitchIndex = jointDePitchIndex.value(), rollIndex = jointDeRollIndex.value(); Vector2 pitchRoll{msg->positions.at(pitchIndex), msg->positions.at(rollIndex)}; - Vector2 motorPositions = 40 * PITCH_ROLL_TO_0_1 * pitchRoll; + Vector2 motorPositions = PITCH_ROLL_TO_01_SCALE * PITCH_ROLL_TO_0_1 * pitchRoll; position.names[pitchIndex] = "joint_de_0"; position.names[rollIndex] = "joint_de_1"; @@ -190,7 +151,7 @@ namespace mrover { auto ArmTranslator::updateDeOffsets(ros::TimerEvent const&) -> void { if (!mJointDePitchRoll) return; - Vector2 motorPositions = 40 * PITCH_ROLL_TO_0_1 * mJointDePitchRoll.value(); + Vector2 motorPositions = PITCH_ROLL_TO_01_SCALE * PITCH_ROLL_TO_0_1 * mJointDePitchRoll.value(); { AdjustMotor adjust; adjust.request.name = "joint_de_0"; diff --git a/src/util/units/units_eigen.hpp b/src/util/units/units_eigen.hpp new file mode 100644 index 000000000..5b1faad7a --- /dev/null +++ b/src/util/units/units_eigen.hpp @@ -0,0 +1,31 @@ +#pragma once + +#include "units.hpp" + +#include + +namespace Eigen { + + template< + typename Rep1, typename Conversion1, typename MeterExp1, typename KilogramExp1, typename SecondExp1, typename RadianExp1, typename AmpereExp1, typename KelvinExp1, typename ByteExp1, typename TickExp1, + typename Rep2, typename Conversion2, typename MeterExp2, typename KilogramExp2, typename SecondExp2, typename RadianExp2, typename AmpereExp2, typename KelvinExp2, typename ByteExp2, typename TickExp2> + struct ScalarBinaryOpTraits< + mrover::Unit, + mrover::Unit, + internal::scalar_product_op< + mrover::Unit, + mrover::Unit>> { + using U1 = mrover::Unit; + using U2 = mrover::Unit; + using ReturnType = mrover::multiply; + }; + + template<> + struct ScalarBinaryOpTraits< + mrover::Dimensionless, + mrover::Dimensionless, + internal::scalar_product_op> { + using ReturnType = mrover::Dimensionless; + }; + +} // namespace Eigen From 8b0543ea7c1ad0838edba0b70787e4f02e11c32f Mon Sep 17 00:00:00 2001 From: qhdwight Date: Wed, 17 Apr 2024 21:44:43 -0400 Subject: [PATCH 02/10] Don't install deps on ci --- .github/workflows/ci.yml | 10 +--------- 1 file changed, 1 insertion(+), 9 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index fe8490c2e..c784b2310 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -22,16 +22,8 @@ jobs: lfs: "true" # This makes sure that $GITHUB_WORKSPACE is the catkin workspace path path: "src/mrover" - - name: Ensure Python Requirements - run: . /home/mrover/catkin_ws/src/mrover/venv/bin/activate && pip install --no-cache-dir -e "$GITHUB_WORKSPACE/src/mrover[dev]" - name: Style Check run: . /home/mrover/catkin_ws/src/mrover/venv/bin/activate && cd $GITHUB_WORKSPACE/src/mrover/ && ./style.sh - - name: Update ROS APT - if: github.event.pull_request.draft == false - run: runuser -u mrover -- rosdep update - - name: Ensure ROS APT Requirements - if: github.event.pull_request.draft == false - run: runuser -u mrover -- rosdep install --from-paths "$GITHUB_WORKSPACE/src" --ignore-src -r -y --rosdistro noetic - name: Copy Catkin Profiles if: github.event.pull_request.draft == false run: rsync -r $GITHUB_WORKSPACE/src/mrover/ansible/roles/build/files/profiles $GITHUB_WORKSPACE/.catkin_tools @@ -42,7 +34,7 @@ jobs: if: github.event.pull_request.draft == false && github.event.pull_request.base.ref != 'refs/heads/master' run: . /opt/ros/noetic/setup.sh && . /home/mrover/catkin_ws/src/mrover/venv/bin/activate && catkin build - name: Build With Clang Tidy - if : github.event_name == 'push' && github.event.pull_request.base.ref == 'refs/heads/master' + if: github.event_name == 'push' && github.event.pull_request.base.ref == 'refs/heads/master' run: . /opt/ros/noetic/setup.sh && . /home/mrover/catkin_ws/src/mrover/venv/bin/activate && catkin build -DCMAKE_CXX_CLANG_TIDY=clang-tidy-16 - name: Test if: github.event.pull_request.draft == false From 14f406a93b4adf303df6e307e6a4a1ada9fe7b74 Mon Sep 17 00:00:00 2001 From: qhdwight Date: Wed, 17 Apr 2024 21:57:43 -0400 Subject: [PATCH 03/10] Fix auton unit test, add spirv tools to ansible --- ansible/roles/build/tasks/main.yml | 1 + test/navigation/drive_test.py | 4 ++-- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/ansible/roles/build/tasks/main.yml b/ansible/roles/build/tasks/main.yml index 6d91a9651..f816bfa99 100644 --- a/ansible/roles/build/tasks/main.yml +++ b/ansible/roles/build/tasks/main.yml @@ -89,6 +89,7 @@ - ros-{{ ros_distro }}-rosbash - libbullet-dev - libglfw3-dev + - spirv-tools - libx11-xcb-dev - libnl-3-dev - libnl-route-3-dev diff --git a/test/navigation/drive_test.py b/test/navigation/drive_test.py index ce8db9fe7..3ca31840c 100755 --- a/test/navigation/drive_test.py +++ b/test/navigation/drive_test.py @@ -45,7 +45,7 @@ def test_turn_right(self): print(cmd) print(done) self.assertLess(cmd.angular.z, 0.0) - self.assertEqual(cmd.angular.z, -1.0) + self.assertEqual(cmd.angular.z, -0.7) self.assertEqual(cmd.linear.x, 0.0) def test_turn_left(self): @@ -59,7 +59,7 @@ def test_turn_left(self): print(cmd) print(done) self.assertGreater(cmd.angular.z, 0.0) - self.assertEqual(cmd.angular.z, 1.0) + self.assertEqual(cmd.angular.z, 0.7) self.assertEqual(cmd.linear.x, 0.0) def test_straight_angle(self): From f39acfec1528f953af1f0547a540a51cbee09bf1 Mon Sep 17 00:00:00 2001 From: qhdwight Date: Wed, 17 Apr 2024 22:38:53 -0400 Subject: [PATCH 04/10] Update dawn, no reliance on shared libasl now and spirv shared --- ansible/roles/build/tasks/main.yml | 1 - pkg/libdawn-dev.deb | 4 ++-- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/ansible/roles/build/tasks/main.yml b/ansible/roles/build/tasks/main.yml index f816bfa99..6d91a9651 100644 --- a/ansible/roles/build/tasks/main.yml +++ b/ansible/roles/build/tasks/main.yml @@ -89,7 +89,6 @@ - ros-{{ ros_distro }}-rosbash - libbullet-dev - libglfw3-dev - - spirv-tools - libx11-xcb-dev - libnl-3-dev - libnl-route-3-dev diff --git a/pkg/libdawn-dev.deb b/pkg/libdawn-dev.deb index e09559416..98a82d987 100644 --- a/pkg/libdawn-dev.deb +++ b/pkg/libdawn-dev.deb @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:e9b96c382fb63ddf331ffd7f900ce060ad4434a4f4a749fc0c8e596d81125d6b -size 5266774 +oid sha256:a71d028745d79b179b6f1fab01bb87bccef31326c7656e3298ca6ba163ebb5f6 +size 4385188 From 6d06b3f93a3aa2bd5a675dc8d7fd6409bce07f92 Mon Sep 17 00:00:00 2001 From: qhdwight Date: Wed, 17 Apr 2024 23:02:45 -0400 Subject: [PATCH 05/10] Comments --- src/esw/arm_hw_bridge/main.cpp | 2 - .../arm_translator_bridge/arm_translator.cpp | 4 +- src/esw/drive_bridge/main.cpp | 21 ++-- src/esw/motor_library/brushless.hpp | 106 +++++++----------- src/esw/motor_library/controller.hpp | 12 -- .../linear_joint_translation.hpp | 15 --- 6 files changed, 52 insertions(+), 108 deletions(-) delete mode 100644 src/esw/motor_library/linear_joint_translation.hpp diff --git a/src/esw/arm_hw_bridge/main.cpp b/src/esw/arm_hw_bridge/main.cpp index 7a3762427..28480cc13 100644 --- a/src/esw/arm_hw_bridge/main.cpp +++ b/src/esw/arm_hw_bridge/main.cpp @@ -13,7 +13,6 @@ auto armLaserCallback(std_srvs::SetBool::Request& req, std_srvs::SetBool::Respon } auto main(int argc, char** argv) -> int { - // Initialize the ROS node ros::init(argc, argv, "arm_hw_bridge"); ros::NodeHandle nh; @@ -23,7 +22,6 @@ auto main(int argc, char** argv) -> int { ros::ServiceServer armLaserService = nh.advertiseService("enable_arm_laser", armLaserCallback); - // Enter the ROS event loop ros::spin(); return EXIT_SUCCESS; diff --git a/src/esw/arm_translator_bridge/arm_translator.cpp b/src/esw/arm_translator_bridge/arm_translator.cpp index 8d1b91924..0be5f66fe 100644 --- a/src/esw/arm_translator_bridge/arm_translator.cpp +++ b/src/esw/arm_translator_bridge/arm_translator.cpp @@ -15,7 +15,7 @@ namespace mrover { Dimensionless static constexpr PITCH_ROLL_TO_01_SCALE{40}; // How often we send an adjust command to the DE motors - // This updates the quadrature motor source on the Moteus based on the absolute encoder readings + // This corrects the HALL-effect motor source on the Moteus based on the absolute encoder readings double static constexpr DE_OFFSET_TIMER_PERIOD = 1; ArmTranslator::ArmTranslator(ros::NodeHandle& nh) { @@ -136,6 +136,8 @@ namespace mrover { std::optional jointDe0Index = findJointByName(msg->name, "joint_de_0"), jointDe1Index = findJointByName(msg->name, "joint_de_1"); if (jointDe0Index && jointDe1Index) { + // The Moteus reports auxiliary motor positions in the range [0, tau) instead of [-pi, pi) + // Wrap to better align with IK conventions auto pitchWrapped = wrapAngle(static_cast(msg->position.at(jointDe0Index.value()))); auto rollWrapped = wrapAngle(static_cast(msg->position.at(jointDe1Index.value()))); mJointDePitchRoll = {pitchWrapped, rollWrapped}; diff --git a/src/esw/drive_bridge/main.cpp b/src/esw/drive_bridge/main.cpp index cc30f11b5..4bcbe86d5 100644 --- a/src/esw/drive_bridge/main.cpp +++ b/src/esw/drive_bridge/main.cpp @@ -5,6 +5,10 @@ #include #include +/* + * Converts from a Twist (linear and angular velocity) to the individual wheel velocities + */ + using namespace mrover; void moveDrive(geometry_msgs::Twist::ConstPtr const& msg); @@ -13,37 +17,26 @@ ros::Publisher leftVelocityPub, rightVelocityPub; Meters WHEEL_DISTANCE_INNER; compound_unit> WHEEL_LINEAR_TO_ANGULAR; -RadiansPerSecond MAX_MOTOR_SPEED; auto main(int argc, char** argv) -> int { - // Initialize the ROS node ros::init(argc, argv, "drive_bridge"); ros::NodeHandle nh; - // Load rover dimensions and other parameters from the ROS parameter server auto roverWidth = requireParamAsUnit(nh, "rover/width"); WHEEL_DISTANCE_INNER = roverWidth / 2; auto ratioMotorToWheel = requireParamAsUnit(nh, "wheel/gear_ratio"); auto wheelRadius = requireParamAsUnit(nh, "wheel/radius"); - // TODO(quintin) is dividing by ratioMotorToWheel right? WHEEL_LINEAR_TO_ANGULAR = Radians{1} / wheelRadius * ratioMotorToWheel; - auto maxLinearSpeed = requireParamAsUnit(nh, "rover/max_speed"); - assert(maxLinearSpeed > 0_mps); - - MAX_MOTOR_SPEED = maxLinearSpeed * WHEEL_LINEAR_TO_ANGULAR; - auto leftGroup = std::make_unique(nh, "drive_left"); auto rightGroup = std::make_unique(nh, "drive_right"); leftVelocityPub = nh.advertise("drive_left_velocity_cmd", 1); rightVelocityPub = nh.advertise("drive_right_velocity_cmd", 1); - // Subscribe to the ROS topic for drive commands auto twistSubscriber = nh.subscribe("cmd_vel", 1, moveDrive); - // Enter the ROS event loop ros::spin(); return 0; @@ -62,14 +55,14 @@ void moveDrive(geometry_msgs::Twist::ConstPtr const& msg) { { Velocity leftVelocity; leftVelocity.names = {"front_left", "middle_left", "back_left"}; - // TODO(quintin): Invert in firmware - leftVelocity.velocities = {-left.get(), -left.get(), -left.get()}; + left *= -1; // TODO(quintin): Invert in firmware instead + leftVelocity.velocities.resize(leftVelocity.names.size(), left.get()); leftVelocityPub.publish(leftVelocity); } { Velocity rightVelocity; rightVelocity.names = {"front_right", "middle_right", "back_right"}; - rightVelocity.velocities = {right.get(), right.get(), right.get()}; + rightVelocity.velocities.resize(rightVelocity.names.size(), right.get()); rightVelocityPub.publish(rightVelocity); } } diff --git a/src/esw/motor_library/brushless.hpp b/src/esw/motor_library/brushless.hpp index fc1437697..a7c1175ea 100644 --- a/src/esw/motor_library/brushless.hpp +++ b/src/esw/motor_library/brushless.hpp @@ -52,8 +52,8 @@ namespace mrover { }; struct MoteusLimitSwitchInfo { - bool isFwdPressed{}; - bool isBwdPressed{}; + bool isForwardPressed{}; + bool isBackwardPressed{}; }; template @@ -118,10 +118,14 @@ namespace mrover { } moteus::Controller::Options options; - moteus::Query::Format queryFormat; + moteus::Query::Format queryFormat{}; queryFormat.aux1_gpio = moteus::kInt8; queryFormat.aux2_gpio = moteus::kInt8; - if (this->isJointDe()) { // add joint de abs slots to CAN message + if (this->isJointDe()) { + // DE0 and DE1 have absolute encoders + // They are not used for their internal control loops + // Instead we request them at the ROS level and send adjust commands periodically + // Therefore we do not get them as part of normal messages and must request them explicitly queryFormat.extra[0] = moteus::Query::ItemFormat{ .register_number = moteus::Register::kEncoder1Position, .resolution = moteus::kFloat, @@ -140,12 +144,13 @@ namespace mrover { } auto setDesiredPosition(OutputPosition position) -> void { - // only check for limit switches if at least one limit switch exists and is enabled + // Only check for limit switches if at least one limit switch exists and is enabled if ((limitSwitch0Enabled && limitSwitch0Present) || (limitSwitch1Enabled && limitSwitch0Present)) { sendQuery(); - MoteusLimitSwitchInfo limitSwitchInfo = getPressedLimitSwitchInfo(); - if ((mCurrentPosition < position && limitSwitchInfo.isFwdPressed) || (mCurrentPosition > position && limitSwitchInfo.isBwdPressed)) { + if (auto [isFwdPressed, isBwdPressed] = getPressedLimitSwitchInfo(); + (mCurrentPosition < position && isFwdPressed) || + (mCurrentPosition > position && isBwdPressed)) { setBrake(); return; } @@ -159,9 +164,6 @@ namespace mrover { .maximum_torque = mMaxTorque, .watchdog_timeout = mWatchdogTimeout, }; - if (this->isJointDe()) { - ROS_INFO_STREAM(std::format("Setting position to {}", position.get()).c_str()); - } moteus::CanFdFrame positionFrame = mMoteus->MakePosition(command); mDevice.publish_moteus_frame(positionFrame); } @@ -170,27 +172,27 @@ namespace mrover { assert(msg->source == mControllerName); assert(msg->destination == mMasterName); auto result = moteus::Query::Parse(msg->data.data(), msg->data.size()); - if (this->isJointDe()) { - ROS_INFO("controller: %s %3d p/a/v/t=(%7.3f,%7.3f,%7.3f,%7.3f) v/t/f=(%5.1f,%5.1f,%3d) GPIO: Aux1-%X , Aux2-%X", - mControllerName.c_str(), - result.mode, - result.position, - result.abs_position, - result.velocity, - result.torque, - result.voltage, - result.temperature, - result.fault, - result.aux1_gpio, - result.aux2_gpio); - } + // if (this->isJointDe()) { + // ROS_INFO("controller: %s %3d p/a/v/t=(%7.3f,%7.3f,%7.3f,%7.3f) v/t/f=(%5.1f,%5.1f,%3d) GPIO: Aux1-%X , Aux2-%X", + // mControllerName.c_str(), + // result.mode, + // result.position, + // result.abs_position, + // result.velocity, + // result.torque, + // result.voltage, + // result.temperature, + // result.fault, + // result.aux1_gpio, + // result.aux2_gpio); + // } if (this->isJointDe()) { - mCurrentPosition = OutputPosition{result.extra[0].value}; // get value of absolute encoder if its joint_de0/1 + mCurrentPosition = OutputPosition{result.extra[0].value}; // Get value of absolute encoder if its joint_de0/1 mCurrentVelocity = OutputVelocity{result.extra[1].value}; } else { - mCurrentPosition = OutputPosition{result.position}; // moteus stores position in revolutions. - mCurrentVelocity = OutputVelocity{result.velocity}; // moteus stores position in revolutions. + mCurrentPosition = OutputPosition{result.position}; + mCurrentVelocity = OutputVelocity{result.velocity}; } mCurrentEffort = result.torque; @@ -207,12 +209,13 @@ namespace mrover { } auto setDesiredVelocity(OutputVelocity velocity) -> void { - // only check for limit switches if at least one limit switch exists and is enabled + // Only check for limit switches if at least one limit switch exists and is enabled if ((limitSwitch0Enabled && limitSwitch0Present) || (limitSwitch1Enabled && limitSwitch0Present)) { sendQuery(); - MoteusLimitSwitchInfo limitSwitchInfo = getPressedLimitSwitchInfo(); - if ((velocity > OutputVelocity{0} && limitSwitchInfo.isFwdPressed) || (velocity < OutputVelocity{0} && limitSwitchInfo.isBwdPressed)) { + if (auto [isFwdPressed, isBwdPressed] = getPressedLimitSwitchInfo(); + (velocity > OutputVelocity{0} && isFwdPressed) || + (velocity < OutputVelocity{0} && isBwdPressed)) { setBrake(); return; } @@ -235,9 +238,7 @@ namespace mrover { } } - auto getEffort() -> double { - // TODO - need to properly set mMeasuredEFfort elsewhere. - // (Art Boyarov): return quiet_Nan, same as Brushed Controller + [[nodiscard]] auto getEffort() const -> double { return mCurrentEffort; } @@ -252,46 +253,23 @@ namespace mrover { } auto getPressedLimitSwitchInfo() -> MoteusLimitSwitchInfo { - /* - Testing 2/9: - - Connected limit switch (common is input(black), NC to ground) - - Configured moteus to have all pins set as digital_input and pull_up - - When limit switch not pressed, aux2 = 0xD - - When limit switch pressed, aux1 = 0xF - - Note: has to be active high, so in this scenario we have to flip this bit round. - - This was connected to just one moteus board, not the one with a motor on it. - - Stuff for Limit Switches (from Guthrie) - - Read from config about limit switch settings - - Either 1 or 0 not forward/backward - - - Add a member variable in Brushless.hpp to store limit switch value. - pdate this limit switch variable every round in ProcessCANMessage. - - - Note: we can get aux pin info even without sending a query command. - Tested with sending velocity commands. - */ - // TODO - implement this - MoteusLimitSwitchInfo result{}; - result.isFwdPressed = false; - result.isBwdPressed = false; - - // Limit switches now wired to AUX2 (index 0 and 1) if (limitSwitch0Present && limitSwitch0Enabled) { bool gpioState = 0b01 & mMoteusAux2Info; - mLimitHit.at(0) = gpioState == limitSwitch0ActiveHigh; + mLimitHit[0] = gpioState == limitSwitch0ActiveHigh; } if (limitSwitch1Present && limitSwitch1Enabled) { bool gpioState = 0b10 & mMoteusAux2Info; - mLimitHit.at(1) = gpioState == limitSwitch1ActiveHigh; + mLimitHit[1] = gpioState == limitSwitch1ActiveHigh; } - result.isFwdPressed = (mLimitHit.at(0) && limitSwitch0LimitsFwd) || (mLimitHit.at(1) && limitSwitch1LimitsFwd); - result.isBwdPressed = (mLimitHit.at(0) && !limitSwitch0LimitsFwd) || (mLimitHit.at(1) && !limitSwitch1LimitsFwd); + MoteusLimitSwitchInfo result{ + .isForwardPressed = (mLimitHit[0] && limitSwitch0LimitsFwd) || (mLimitHit[1] && limitSwitch1LimitsFwd), + .isBackwardPressed = (mLimitHit[0] && !limitSwitch0LimitsFwd) || (mLimitHit[1] && !limitSwitch1LimitsFwd), + }; - if (result.isFwdPressed) { + if (result.isForwardPressed) { adjust(limitSwitch0ReadjustPosition); - } else if (result.isBwdPressed) { + } else if (result.isBackwardPressed) { adjust(limitSwitch1ReadjustPosition); } diff --git a/src/esw/motor_library/controller.hpp b/src/esw/motor_library/controller.hpp index a608cd46f..3e14043b2 100644 --- a/src/esw/motor_library/controller.hpp +++ b/src/esw/motor_library/controller.hpp @@ -37,7 +37,6 @@ namespace mrover { mMoveThrottleSub{mNh.subscribe(std::format("{}_throttle_cmd", mControllerName), 1, &ControllerBase::setDesiredThrottle, this)}, mMoveVelocitySub{mNh.subscribe(std::format("{}_velocity_cmd", mControllerName), 1, &ControllerBase::setDesiredVelocity, this)}, mMovePositionSub{mNh.subscribe(std::format("{}_position_cmd", mControllerName), 1, &ControllerBase::setDesiredPosition, this)}, - // mAdjustEncoderSub{mNh.subscribe(std::format("{}_adjust_cmd", mControllerName), 1, &ControllerBase::adjustEncoder, this)}, mJointDataPub{mNh.advertise(std::format("{}_joint_data", mControllerName), 1)}, mControllerDataPub{mNh.advertise(std::format("{}_controller_data", mControllerName), 1)}, mPublishDataTimer{mNh.createTimer(ros::Duration{0.1}, &ControllerBase::publishDataCallback, this)}, @@ -88,17 +87,6 @@ namespace mrover { static_cast(this)->setDesiredPosition(position); } - auto adjustEncoder(MotorsAdjust::ConstPtr const& msg) -> void { - if (msg->names.size() != 1 || msg->names.at(0) != mControllerName || msg->values.size() != 1) { - ROS_ERROR("Adjust request at topic for %s ignored!", msg->names.at(0).c_str()); - return; - } - - using Position = typename detail::strip_conversion::type; - OutputPosition position = Position{msg->values.front()}; - static_cast(this)->adjust(position); - } - [[nodiscard]] auto isJointDe() const -> bool { return mControllerName == "joint_de_0" || mControllerName == "joint_de_1"; } diff --git a/src/esw/motor_library/linear_joint_translation.hpp b/src/esw/motor_library/linear_joint_translation.hpp deleted file mode 100644 index 1d7924ec3..000000000 --- a/src/esw/motor_library/linear_joint_translation.hpp +++ /dev/null @@ -1,15 +0,0 @@ -#pragma once - -#include - -namespace mrover { - - auto inline convertLinVel(float velocity, float multiplier) { - return velocity * multiplier; - } - - auto inline convertLinPos(float position, float multiplier) { - return position * multiplier; - } - -} // namespace mrover From 90d365c97b64209f2fc5eee4428f978bbca7dcaf Mon Sep 17 00:00:00 2001 From: qhdwight Date: Thu, 18 Apr 2024 14:25:27 -0400 Subject: [PATCH 06/10] Remove joystick x axis for turning (only use twist), apply quadratic for linear speed --- src/teleoperation/backend/consumers.py | 102 ++++++++++++------------- 1 file changed, 49 insertions(+), 53 deletions(-) diff --git a/src/teleoperation/backend/consumers.py b/src/teleoperation/backend/consumers.py index d5bc057b8..911c86f33 100644 --- a/src/teleoperation/backend/consumers.py +++ b/src/teleoperation/backend/consumers.py @@ -1,17 +1,17 @@ import csv -from datetime import datetime import json import os -import pytz -from math import copysign -from math import pi -from tf.transformations import euler_from_quaternion import threading +from datetime import datetime +from math import copysign, pi +import pytz from channels.generic.websocket import JsonWebsocketConsumer + import rospy import tf2_ros -import cv2 +from backend.models import AutonWaypoint, BasicWaypoint +from geometry_msgs.msg import Twist, Pose, Point, Quaternion, Vector3 # from cv_bridge import CvBridge from mrover.msg import ( @@ -33,30 +33,31 @@ HeaterData, ) from mrover.srv import EnableAuton, AdjustMotor, ChangeCameras, CapturePanorama -from sensor_msgs.msg import NavSatFix, Temperature, RelativeHumidity, Image +from sensor_msgs.msg import NavSatFix, Temperature, RelativeHumidity from std_msgs.msg import String from std_srvs.srv import SetBool, Trigger -from geometry_msgs.msg import Twist, Pose, Point, Quaternion - +from tf.transformations import euler_from_quaternion from util.SE3 import SE3 -from backend.models import AutonWaypoint, BasicWaypoint - DEFAULT_ARM_DEADZONE = 0.15 -# If below threshold, make output zero -def deadzone(magnitude: float, threshold: float) -> float: - temp_mag = abs(magnitude) - if temp_mag <= threshold: - temp_mag = 0 - else: - temp_mag = (temp_mag - threshold) / (1 - threshold) - return copysign(temp_mag, magnitude) +def deadzone(signal: float, threshold: float) -> float: + """ + Values lower than the threshold will be clipped to zero. + Those above will be remapped to [0, 1] linearly. + """ + magnitude = abs(signal) + magnitude = 0 if magnitude < threshold else (magnitude - threshold) / (1 - threshold) + return copysign(magnitude, signal) -def quadratic(val: float) -> float: - return copysign(val**2, val) +def quadratic(signal: float) -> float: + """ + Use to allow more control near low inputs values by squaring the magnitude. + For example using a joystick to control drive. + """ + return copysign(signal**2, signal) class GUIConsumer(JsonWebsocketConsumer): @@ -409,47 +410,42 @@ def handle_joystick_message(self, msg): # Tiny deadzone so we can safely e-stop with dampen switch dampen = deadzone(msg["axes"][self.mappings["dampen"]], 0.01) - # Makes dampen [0,1] instead of [-1,1] - # negative sign required to drive forward by default instead of backward - # (-1*dampen) because the top of the dampen switch is -1.0 + # Makes dampen [0,1] instead of [-1,1]. + # Negative sign required to drive forward by default instead of backward. + # (-1*dampen) because the top of the dampen switch is -1. dampen = -1 * ((-1 * dampen) + 1) / 2 - linear = deadzone( - msg["axes"][self.mappings["forward_back"]] * self.drive_config["forward_back"]["multiplier"], 0.05 - ) - - # Convert from [0,1] to [0, self_max_wheel_speed] and apply dampen - linear *= self.max_wheel_speed * dampen - - # Deadzones for each axis - left_right = ( - deadzone(msg["axes"][self.mappings["left_right"]] * self.drive_config["left_right"]["multiplier"], 0.4) - if self.drive_config["left_right"]["enabled"] - else 0 + def get_axes_input( + mapping_name: str, deadzone_threshold: float = 0.05, apply_quadratic: bool = False, scale: float = 1.0 + ) -> float: + signal = msg["axes"][self.mappings[mapping_name]] + signal *= self.drive_config[mapping_name]["multiplier"] + signal = deadzone(signal, deadzone_threshold) + if apply_quadratic: + signal = quadratic(signal) + signal *= scale + return signal + + linear = get_axes_input("forward_back", 0.05, True, self.max_wheel_speed * dampen) + # Note(quintin): I prefer using solely the twist axis for turning... + # angular_from_lateral = get_axes_input("left_right", 0.4, True) + angular = get_axes_input("twist", 0.1, True, self.max_angular_speed * dampen) + + self.twist_pub.publish( + Twist( + linear=Vector3(x=linear), + angular=Vector3(z=angular), + ) ) - twist = quadratic(deadzone(msg["axes"][self.mappings["twist"]] * self.drive_config["twist"]["multiplier"], 0.1)) - - angular = twist + left_right - - # Same as linear but for angular speed - angular *= self.max_angular_speed * dampen - # Clamp if both twist and left_right are used at the same time - if abs(angular) > self.max_angular_speed: - angular = copysign(self.max_angular_speed, angular) - twist_msg = Twist() - twist_msg.linear.x = linear - twist_msg.angular.z = angular - - self.twist_pub.publish(twist_msg) self.send( text_data=json.dumps( { "type": "joystick", - "left_right": left_right, + "left_right": msg["axes"][self.mappings["left_right"]], "forward_back": msg["axes"][self.mappings["forward_back"]], - "twist": twist, - "dampen": dampen, + "twist": msg["axes"][self.mappings["twist"]], + "dampen": msg["axes"][self.mappings["dampen"]], "pan": msg["axes"][self.mappings["pan"]], "tilt": msg["axes"][self.mappings["tilt"]], } From 6fc6787e8383ed45c3742a875c62a61c0f37bde5 Mon Sep 17 00:00:00 2001 From: qhdwight Date: Thu, 18 Apr 2024 16:55:47 -0400 Subject: [PATCH 07/10] Add moteus drive config --- config/moteus/back_left.cfg | 1397 ++++++++++++++++++++++++++++++++ config/moteus/back_right.cfg | 350 ++++++++ config/moteus/front_left.cfg | 1397 ++++++++++++++++++++++++++++++++ config/moteus/front_right.cfg | 1397 ++++++++++++++++++++++++++++++++ config/moteus/middle_left.cfg | 1397 ++++++++++++++++++++++++++++++++ config/moteus/middle_right.cfg | 1397 ++++++++++++++++++++++++++++++++ 6 files changed, 7335 insertions(+) create mode 100644 config/moteus/back_left.cfg create mode 100644 config/moteus/back_right.cfg create mode 100644 config/moteus/front_left.cfg create mode 100644 config/moteus/front_right.cfg create mode 100644 config/moteus/middle_left.cfg create mode 100644 config/moteus/middle_right.cfg diff --git a/config/moteus/back_left.cfg b/config/moteus/back_left.cfg new file mode 100644 index 000000000..ad86539b4 --- /dev/null +++ b/config/moteus/back_left.cfg @@ -0,0 +1,1397 @@ +uuid.uuid.0 149 +uuid.uuid.1 226 +uuid.uuid.2 10 +uuid.uuid.3 140 +uuid.uuid.4 38 +uuid.uuid.5 208 +uuid.uuid.6 66 +uuid.uuid.7 69 +uuid.uuid.8 174 +uuid.uuid.9 196 +uuid.uuid.10 56 +uuid.uuid.11 198 +uuid.uuid.12 118 +uuid.uuid.13 164 +uuid.uuid.14 192 +uuid.uuid.15 153 +clock.hsitrim 64 +aux1.i2c.i2c_hz 400000 +aux1.i2c.i2c_mode 1 +aux1.i2c.pullup 0 +aux1.i2c.devices.0.type 0 +aux1.i2c.devices.0.address 64 +aux1.i2c.devices.0.poll_ms 10 +aux1.i2c.devices.1.type 0 +aux1.i2c.devices.1.address 64 +aux1.i2c.devices.1.poll_ms 10 +aux1.i2c.devices.2.type 0 +aux1.i2c.devices.2.address 64 +aux1.i2c.devices.2.poll_ms 10 +aux1.spi.mode 1 +aux1.spi.rate_hz 12000000 +aux1.spi.filter_us 64 +aux1.spi.bct 0 +aux1.uart.mode 0 +aux1.uart.baud_rate 115200 +aux1.uart.poll_rate_us 100 +aux1.uart.rs422 0 +aux1.uart.cui_amt21_address 84 +aux1.quadrature.enabled 0 +aux1.quadrature.cpr 16384 +aux1.hall.enabled 1 +aux1.hall.polarity 0 +aux1.index.enabled 0 +aux1.sine_cosine.enabled 0 +aux1.sine_cosine.common 1700 +aux1.i2c_startup_delay_ms 30 +aux1.pins.0.mode 6 +aux1.pins.0.pull 1 +aux1.pins.1.mode 6 +aux1.pins.1.pull 1 +aux1.pins.2.mode 6 +aux1.pins.2.pull 1 +aux1.pins.3.mode 0 +aux1.pins.3.pull 0 +aux1.pins.4.mode 0 +aux1.pins.4.pull 0 +aux2.i2c.i2c_hz 400000 +aux2.i2c.i2c_mode 1 +aux2.i2c.pullup 0 +aux2.i2c.devices.0.type 0 +aux2.i2c.devices.0.address 64 +aux2.i2c.devices.0.poll_ms 10 +aux2.i2c.devices.1.type 0 +aux2.i2c.devices.1.address 64 +aux2.i2c.devices.1.poll_ms 10 +aux2.i2c.devices.2.type 0 +aux2.i2c.devices.2.address 64 +aux2.i2c.devices.2.poll_ms 10 +aux2.spi.mode 1 +aux2.spi.rate_hz 12000000 +aux2.spi.filter_us 64 +aux2.spi.bct 0 +aux2.uart.mode 0 +aux2.uart.baud_rate 115200 +aux2.uart.poll_rate_us 100 +aux2.uart.rs422 0 +aux2.uart.cui_amt21_address 84 +aux2.quadrature.enabled 0 +aux2.quadrature.cpr 16384 +aux2.hall.enabled 1 +aux2.hall.polarity 0 +aux2.index.enabled 0 +aux2.sine_cosine.enabled 0 +aux2.sine_cosine.common 1700 +aux2.i2c_startup_delay_ms 30 +aux2.pins.0.mode 6 +aux2.pins.0.pull 1 +aux2.pins.1.mode 6 +aux2.pins.1.pull 1 +aux2.pins.2.mode 6 +aux2.pins.2.pull 1 +aux2.pins.3.mode 0 +aux2.pins.3.pull 0 +aux2.pins.4.mode 0 +aux2.pins.4.pull 0 +motor_position.sources.0.aux_number 1 +motor_position.sources.0.type 4 +motor_position.sources.0.i2c_device 0 +motor_position.sources.0.incremental_index -1 +motor_position.sources.0.cpr 84 +motor_position.sources.0.offset -3.000000 +motor_position.sources.0.sign 1 +motor_position.sources.0.debug_override -1 +motor_position.sources.0.reference 0 +motor_position.sources.0.pll_filter_hz 80.000000 +motor_position.sources.0.compensation_table.0 0.000000 +motor_position.sources.0.compensation_table.1 0.000000 +motor_position.sources.0.compensation_table.2 0.000000 +motor_position.sources.0.compensation_table.3 0.000000 +motor_position.sources.0.compensation_table.4 0.000000 +motor_position.sources.0.compensation_table.5 0.000000 +motor_position.sources.0.compensation_table.6 0.000000 +motor_position.sources.0.compensation_table.7 0.000000 +motor_position.sources.0.compensation_table.8 0.000000 +motor_position.sources.0.compensation_table.9 0.000000 +motor_position.sources.0.compensation_table.10 0.000000 +motor_position.sources.0.compensation_table.11 0.000000 +motor_position.sources.0.compensation_table.12 0.000000 +motor_position.sources.0.compensation_table.13 0.000000 +motor_position.sources.0.compensation_table.14 0.000000 +motor_position.sources.0.compensation_table.15 0.000000 +motor_position.sources.0.compensation_table.16 0.000000 +motor_position.sources.0.compensation_table.17 0.000000 +motor_position.sources.0.compensation_table.18 0.000000 +motor_position.sources.0.compensation_table.19 0.000000 +motor_position.sources.0.compensation_table.20 0.000000 +motor_position.sources.0.compensation_table.21 0.000000 +motor_position.sources.0.compensation_table.22 0.000000 +motor_position.sources.0.compensation_table.23 0.000000 +motor_position.sources.0.compensation_table.24 0.000000 +motor_position.sources.0.compensation_table.25 0.000000 +motor_position.sources.0.compensation_table.26 0.000000 +motor_position.sources.0.compensation_table.27 0.000000 +motor_position.sources.0.compensation_table.28 0.000000 +motor_position.sources.0.compensation_table.29 0.000000 +motor_position.sources.0.compensation_table.30 0.000000 +motor_position.sources.0.compensation_table.31 0.000000 +motor_position.sources.1.aux_number 1 +motor_position.sources.1.type 0 +motor_position.sources.1.i2c_device 0 +motor_position.sources.1.incremental_index -1 +motor_position.sources.1.cpr 16384 +motor_position.sources.1.offset 0.000000 +motor_position.sources.1.sign 1 +motor_position.sources.1.debug_override -1 +motor_position.sources.1.reference 0 +motor_position.sources.1.pll_filter_hz 400.000000 +motor_position.sources.1.compensation_table.0 0.000000 +motor_position.sources.1.compensation_table.1 0.000000 +motor_position.sources.1.compensation_table.2 0.000000 +motor_position.sources.1.compensation_table.3 0.000000 +motor_position.sources.1.compensation_table.4 0.000000 +motor_position.sources.1.compensation_table.5 0.000000 +motor_position.sources.1.compensation_table.6 0.000000 +motor_position.sources.1.compensation_table.7 0.000000 +motor_position.sources.1.compensation_table.8 0.000000 +motor_position.sources.1.compensation_table.9 0.000000 +motor_position.sources.1.compensation_table.10 0.000000 +motor_position.sources.1.compensation_table.11 0.000000 +motor_position.sources.1.compensation_table.12 0.000000 +motor_position.sources.1.compensation_table.13 0.000000 +motor_position.sources.1.compensation_table.14 0.000000 +motor_position.sources.1.compensation_table.15 0.000000 +motor_position.sources.1.compensation_table.16 0.000000 +motor_position.sources.1.compensation_table.17 0.000000 +motor_position.sources.1.compensation_table.18 0.000000 +motor_position.sources.1.compensation_table.19 0.000000 +motor_position.sources.1.compensation_table.20 0.000000 +motor_position.sources.1.compensation_table.21 0.000000 +motor_position.sources.1.compensation_table.22 0.000000 +motor_position.sources.1.compensation_table.23 0.000000 +motor_position.sources.1.compensation_table.24 0.000000 +motor_position.sources.1.compensation_table.25 0.000000 +motor_position.sources.1.compensation_table.26 0.000000 +motor_position.sources.1.compensation_table.27 0.000000 +motor_position.sources.1.compensation_table.28 0.000000 +motor_position.sources.1.compensation_table.29 0.000000 +motor_position.sources.1.compensation_table.30 0.000000 +motor_position.sources.1.compensation_table.31 0.000000 +motor_position.sources.2.aux_number 1 +motor_position.sources.2.type 0 +motor_position.sources.2.i2c_device 0 +motor_position.sources.2.incremental_index -1 +motor_position.sources.2.cpr 16384 +motor_position.sources.2.offset 0.000000 +motor_position.sources.2.sign 1 +motor_position.sources.2.debug_override -1 +motor_position.sources.2.reference 0 +motor_position.sources.2.pll_filter_hz 400.000000 +motor_position.sources.2.compensation_table.0 0.000000 +motor_position.sources.2.compensation_table.1 0.000000 +motor_position.sources.2.compensation_table.2 0.000000 +motor_position.sources.2.compensation_table.3 0.000000 +motor_position.sources.2.compensation_table.4 0.000000 +motor_position.sources.2.compensation_table.5 0.000000 +motor_position.sources.2.compensation_table.6 0.000000 +motor_position.sources.2.compensation_table.7 0.000000 +motor_position.sources.2.compensation_table.8 0.000000 +motor_position.sources.2.compensation_table.9 0.000000 +motor_position.sources.2.compensation_table.10 0.000000 +motor_position.sources.2.compensation_table.11 0.000000 +motor_position.sources.2.compensation_table.12 0.000000 +motor_position.sources.2.compensation_table.13 0.000000 +motor_position.sources.2.compensation_table.14 0.000000 +motor_position.sources.2.compensation_table.15 0.000000 +motor_position.sources.2.compensation_table.16 0.000000 +motor_position.sources.2.compensation_table.17 0.000000 +motor_position.sources.2.compensation_table.18 0.000000 +motor_position.sources.2.compensation_table.19 0.000000 +motor_position.sources.2.compensation_table.20 0.000000 +motor_position.sources.2.compensation_table.21 0.000000 +motor_position.sources.2.compensation_table.22 0.000000 +motor_position.sources.2.compensation_table.23 0.000000 +motor_position.sources.2.compensation_table.24 0.000000 +motor_position.sources.2.compensation_table.25 0.000000 +motor_position.sources.2.compensation_table.26 0.000000 +motor_position.sources.2.compensation_table.27 0.000000 +motor_position.sources.2.compensation_table.28 0.000000 +motor_position.sources.2.compensation_table.29 0.000000 +motor_position.sources.2.compensation_table.30 0.000000 +motor_position.sources.2.compensation_table.31 0.000000 +motor_position.commutation_source 0 +motor_position.output.source 0 +motor_position.output.offset 0.000000 +motor_position.output.sign -1 +motor_position.output.reference_source -1 +motor_position.rotor_to_output_ratio 1.000000 +motor.poles 28 +motor.phase_invert 0 +motor.resistance_ohm 0.258464 +motor.v_per_hz 0.409335 +motor.offset.0 0.000000 +motor.offset.1 0.000000 +motor.offset.2 0.000000 +motor.offset.3 0.000000 +motor.offset.4 0.000000 +motor.offset.5 0.000000 +motor.offset.6 0.000000 +motor.offset.7 0.000000 +motor.offset.8 0.000000 +motor.offset.9 0.000000 +motor.offset.10 0.000000 +motor.offset.11 0.000000 +motor.offset.12 0.000000 +motor.offset.13 0.000000 +motor.offset.14 0.000000 +motor.offset.15 0.000000 +motor.offset.16 0.000000 +motor.offset.17 0.000000 +motor.offset.18 0.000000 +motor.offset.19 0.000000 +motor.offset.20 0.000000 +motor.offset.21 0.000000 +motor.offset.22 0.000000 +motor.offset.23 0.000000 +motor.offset.24 0.000000 +motor.offset.25 0.000000 +motor.offset.26 0.000000 +motor.offset.27 0.000000 +motor.offset.28 0.000000 +motor.offset.29 0.000000 +motor.offset.30 0.000000 +motor.offset.31 0.000000 +motor.offset.32 0.000000 +motor.offset.33 0.000000 +motor.offset.34 0.000000 +motor.offset.35 0.000000 +motor.offset.36 0.000000 +motor.offset.37 0.000000 +motor.offset.38 0.000000 +motor.offset.39 0.000000 +motor.offset.40 0.000000 +motor.offset.41 0.000000 +motor.offset.42 0.000000 +motor.offset.43 0.000000 +motor.offset.44 0.000000 +motor.offset.45 0.000000 +motor.offset.46 0.000000 +motor.offset.47 0.000000 +motor.offset.48 0.000000 +motor.offset.49 0.000000 +motor.offset.50 0.000000 +motor.offset.51 0.000000 +motor.offset.52 0.000000 +motor.offset.53 0.000000 +motor.offset.54 0.000000 +motor.offset.55 0.000000 +motor.offset.56 0.000000 +motor.offset.57 0.000000 +motor.offset.58 0.000000 +motor.offset.59 0.000000 +motor.offset.60 0.000000 +motor.offset.61 0.000000 +motor.offset.62 0.000000 +motor.offset.63 0.000000 +motor.rotation_current_cutoff_A 10000.000000 +motor.rotation_current_scale 0.050000 +motor.rotation_torque_scale 14.700000 +motor.cogging_dq_scale 0.000000 +motor.cogging_dq_comp.0 0 +motor.cogging_dq_comp.1 0 +motor.cogging_dq_comp.2 0 +motor.cogging_dq_comp.3 0 +motor.cogging_dq_comp.4 0 +motor.cogging_dq_comp.5 0 +motor.cogging_dq_comp.6 0 +motor.cogging_dq_comp.7 0 +motor.cogging_dq_comp.8 0 +motor.cogging_dq_comp.9 0 +motor.cogging_dq_comp.10 0 +motor.cogging_dq_comp.11 0 +motor.cogging_dq_comp.12 0 +motor.cogging_dq_comp.13 0 +motor.cogging_dq_comp.14 0 +motor.cogging_dq_comp.15 0 +motor.cogging_dq_comp.16 0 +motor.cogging_dq_comp.17 0 +motor.cogging_dq_comp.18 0 +motor.cogging_dq_comp.19 0 +motor.cogging_dq_comp.20 0 +motor.cogging_dq_comp.21 0 +motor.cogging_dq_comp.22 0 +motor.cogging_dq_comp.23 0 +motor.cogging_dq_comp.24 0 +motor.cogging_dq_comp.25 0 +motor.cogging_dq_comp.26 0 +motor.cogging_dq_comp.27 0 +motor.cogging_dq_comp.28 0 +motor.cogging_dq_comp.29 0 +motor.cogging_dq_comp.30 0 +motor.cogging_dq_comp.31 0 +motor.cogging_dq_comp.32 0 +motor.cogging_dq_comp.33 0 +motor.cogging_dq_comp.34 0 +motor.cogging_dq_comp.35 0 +motor.cogging_dq_comp.36 0 +motor.cogging_dq_comp.37 0 +motor.cogging_dq_comp.38 0 +motor.cogging_dq_comp.39 0 +motor.cogging_dq_comp.40 0 +motor.cogging_dq_comp.41 0 +motor.cogging_dq_comp.42 0 +motor.cogging_dq_comp.43 0 +motor.cogging_dq_comp.44 0 +motor.cogging_dq_comp.45 0 +motor.cogging_dq_comp.46 0 +motor.cogging_dq_comp.47 0 +motor.cogging_dq_comp.48 0 +motor.cogging_dq_comp.49 0 +motor.cogging_dq_comp.50 0 +motor.cogging_dq_comp.51 0 +motor.cogging_dq_comp.52 0 +motor.cogging_dq_comp.53 0 +motor.cogging_dq_comp.54 0 +motor.cogging_dq_comp.55 0 +motor.cogging_dq_comp.56 0 +motor.cogging_dq_comp.57 0 +motor.cogging_dq_comp.58 0 +motor.cogging_dq_comp.59 0 +motor.cogging_dq_comp.60 0 +motor.cogging_dq_comp.61 0 +motor.cogging_dq_comp.62 0 +motor.cogging_dq_comp.63 0 +motor.cogging_dq_comp.64 0 +motor.cogging_dq_comp.65 0 +motor.cogging_dq_comp.66 0 +motor.cogging_dq_comp.67 0 +motor.cogging_dq_comp.68 0 +motor.cogging_dq_comp.69 0 +motor.cogging_dq_comp.70 0 +motor.cogging_dq_comp.71 0 +motor.cogging_dq_comp.72 0 +motor.cogging_dq_comp.73 0 +motor.cogging_dq_comp.74 0 +motor.cogging_dq_comp.75 0 +motor.cogging_dq_comp.76 0 +motor.cogging_dq_comp.77 0 +motor.cogging_dq_comp.78 0 +motor.cogging_dq_comp.79 0 +motor.cogging_dq_comp.80 0 +motor.cogging_dq_comp.81 0 +motor.cogging_dq_comp.82 0 +motor.cogging_dq_comp.83 0 +motor.cogging_dq_comp.84 0 +motor.cogging_dq_comp.85 0 +motor.cogging_dq_comp.86 0 +motor.cogging_dq_comp.87 0 +motor.cogging_dq_comp.88 0 +motor.cogging_dq_comp.89 0 +motor.cogging_dq_comp.90 0 +motor.cogging_dq_comp.91 0 +motor.cogging_dq_comp.92 0 +motor.cogging_dq_comp.93 0 +motor.cogging_dq_comp.94 0 +motor.cogging_dq_comp.95 0 +motor.cogging_dq_comp.96 0 +motor.cogging_dq_comp.97 0 +motor.cogging_dq_comp.98 0 +motor.cogging_dq_comp.99 0 +motor.cogging_dq_comp.100 0 +motor.cogging_dq_comp.101 0 +motor.cogging_dq_comp.102 0 +motor.cogging_dq_comp.103 0 +motor.cogging_dq_comp.104 0 +motor.cogging_dq_comp.105 0 +motor.cogging_dq_comp.106 0 +motor.cogging_dq_comp.107 0 +motor.cogging_dq_comp.108 0 +motor.cogging_dq_comp.109 0 +motor.cogging_dq_comp.110 0 +motor.cogging_dq_comp.111 0 +motor.cogging_dq_comp.112 0 +motor.cogging_dq_comp.113 0 +motor.cogging_dq_comp.114 0 +motor.cogging_dq_comp.115 0 +motor.cogging_dq_comp.116 0 +motor.cogging_dq_comp.117 0 +motor.cogging_dq_comp.118 0 +motor.cogging_dq_comp.119 0 +motor.cogging_dq_comp.120 0 +motor.cogging_dq_comp.121 0 +motor.cogging_dq_comp.122 0 +motor.cogging_dq_comp.123 0 +motor.cogging_dq_comp.124 0 +motor.cogging_dq_comp.125 0 +motor.cogging_dq_comp.126 0 +motor.cogging_dq_comp.127 0 +motor.cogging_dq_comp.128 0 +motor.cogging_dq_comp.129 0 +motor.cogging_dq_comp.130 0 +motor.cogging_dq_comp.131 0 +motor.cogging_dq_comp.132 0 +motor.cogging_dq_comp.133 0 +motor.cogging_dq_comp.134 0 +motor.cogging_dq_comp.135 0 +motor.cogging_dq_comp.136 0 +motor.cogging_dq_comp.137 0 +motor.cogging_dq_comp.138 0 +motor.cogging_dq_comp.139 0 +motor.cogging_dq_comp.140 0 +motor.cogging_dq_comp.141 0 +motor.cogging_dq_comp.142 0 +motor.cogging_dq_comp.143 0 +motor.cogging_dq_comp.144 0 +motor.cogging_dq_comp.145 0 +motor.cogging_dq_comp.146 0 +motor.cogging_dq_comp.147 0 +motor.cogging_dq_comp.148 0 +motor.cogging_dq_comp.149 0 +motor.cogging_dq_comp.150 0 +motor.cogging_dq_comp.151 0 +motor.cogging_dq_comp.152 0 +motor.cogging_dq_comp.153 0 +motor.cogging_dq_comp.154 0 +motor.cogging_dq_comp.155 0 +motor.cogging_dq_comp.156 0 +motor.cogging_dq_comp.157 0 +motor.cogging_dq_comp.158 0 +motor.cogging_dq_comp.159 0 +motor.cogging_dq_comp.160 0 +motor.cogging_dq_comp.161 0 +motor.cogging_dq_comp.162 0 +motor.cogging_dq_comp.163 0 +motor.cogging_dq_comp.164 0 +motor.cogging_dq_comp.165 0 +motor.cogging_dq_comp.166 0 +motor.cogging_dq_comp.167 0 +motor.cogging_dq_comp.168 0 +motor.cogging_dq_comp.169 0 +motor.cogging_dq_comp.170 0 +motor.cogging_dq_comp.171 0 +motor.cogging_dq_comp.172 0 +motor.cogging_dq_comp.173 0 +motor.cogging_dq_comp.174 0 +motor.cogging_dq_comp.175 0 +motor.cogging_dq_comp.176 0 +motor.cogging_dq_comp.177 0 +motor.cogging_dq_comp.178 0 +motor.cogging_dq_comp.179 0 +motor.cogging_dq_comp.180 0 +motor.cogging_dq_comp.181 0 +motor.cogging_dq_comp.182 0 +motor.cogging_dq_comp.183 0 +motor.cogging_dq_comp.184 0 +motor.cogging_dq_comp.185 0 +motor.cogging_dq_comp.186 0 +motor.cogging_dq_comp.187 0 +motor.cogging_dq_comp.188 0 +motor.cogging_dq_comp.189 0 +motor.cogging_dq_comp.190 0 +motor.cogging_dq_comp.191 0 +motor.cogging_dq_comp.192 0 +motor.cogging_dq_comp.193 0 +motor.cogging_dq_comp.194 0 +motor.cogging_dq_comp.195 0 +motor.cogging_dq_comp.196 0 +motor.cogging_dq_comp.197 0 +motor.cogging_dq_comp.198 0 +motor.cogging_dq_comp.199 0 +motor.cogging_dq_comp.200 0 +motor.cogging_dq_comp.201 0 +motor.cogging_dq_comp.202 0 +motor.cogging_dq_comp.203 0 +motor.cogging_dq_comp.204 0 +motor.cogging_dq_comp.205 0 +motor.cogging_dq_comp.206 0 +motor.cogging_dq_comp.207 0 +motor.cogging_dq_comp.208 0 +motor.cogging_dq_comp.209 0 +motor.cogging_dq_comp.210 0 +motor.cogging_dq_comp.211 0 +motor.cogging_dq_comp.212 0 +motor.cogging_dq_comp.213 0 +motor.cogging_dq_comp.214 0 +motor.cogging_dq_comp.215 0 +motor.cogging_dq_comp.216 0 +motor.cogging_dq_comp.217 0 +motor.cogging_dq_comp.218 0 +motor.cogging_dq_comp.219 0 +motor.cogging_dq_comp.220 0 +motor.cogging_dq_comp.221 0 +motor.cogging_dq_comp.222 0 +motor.cogging_dq_comp.223 0 +motor.cogging_dq_comp.224 0 +motor.cogging_dq_comp.225 0 +motor.cogging_dq_comp.226 0 +motor.cogging_dq_comp.227 0 +motor.cogging_dq_comp.228 0 +motor.cogging_dq_comp.229 0 +motor.cogging_dq_comp.230 0 +motor.cogging_dq_comp.231 0 +motor.cogging_dq_comp.232 0 +motor.cogging_dq_comp.233 0 +motor.cogging_dq_comp.234 0 +motor.cogging_dq_comp.235 0 +motor.cogging_dq_comp.236 0 +motor.cogging_dq_comp.237 0 +motor.cogging_dq_comp.238 0 +motor.cogging_dq_comp.239 0 +motor.cogging_dq_comp.240 0 +motor.cogging_dq_comp.241 0 +motor.cogging_dq_comp.242 0 +motor.cogging_dq_comp.243 0 +motor.cogging_dq_comp.244 0 +motor.cogging_dq_comp.245 0 +motor.cogging_dq_comp.246 0 +motor.cogging_dq_comp.247 0 +motor.cogging_dq_comp.248 0 +motor.cogging_dq_comp.249 0 +motor.cogging_dq_comp.250 0 +motor.cogging_dq_comp.251 0 +motor.cogging_dq_comp.252 0 +motor.cogging_dq_comp.253 0 +motor.cogging_dq_comp.254 0 +motor.cogging_dq_comp.255 0 +motor.cogging_dq_comp.256 0 +motor.cogging_dq_comp.257 0 +motor.cogging_dq_comp.258 0 +motor.cogging_dq_comp.259 0 +motor.cogging_dq_comp.260 0 +motor.cogging_dq_comp.261 0 +motor.cogging_dq_comp.262 0 +motor.cogging_dq_comp.263 0 +motor.cogging_dq_comp.264 0 +motor.cogging_dq_comp.265 0 +motor.cogging_dq_comp.266 0 +motor.cogging_dq_comp.267 0 +motor.cogging_dq_comp.268 0 +motor.cogging_dq_comp.269 0 +motor.cogging_dq_comp.270 0 +motor.cogging_dq_comp.271 0 +motor.cogging_dq_comp.272 0 +motor.cogging_dq_comp.273 0 +motor.cogging_dq_comp.274 0 +motor.cogging_dq_comp.275 0 +motor.cogging_dq_comp.276 0 +motor.cogging_dq_comp.277 0 +motor.cogging_dq_comp.278 0 +motor.cogging_dq_comp.279 0 +motor.cogging_dq_comp.280 0 +motor.cogging_dq_comp.281 0 +motor.cogging_dq_comp.282 0 +motor.cogging_dq_comp.283 0 +motor.cogging_dq_comp.284 0 +motor.cogging_dq_comp.285 0 +motor.cogging_dq_comp.286 0 +motor.cogging_dq_comp.287 0 +motor.cogging_dq_comp.288 0 +motor.cogging_dq_comp.289 0 +motor.cogging_dq_comp.290 0 +motor.cogging_dq_comp.291 0 +motor.cogging_dq_comp.292 0 +motor.cogging_dq_comp.293 0 +motor.cogging_dq_comp.294 0 +motor.cogging_dq_comp.295 0 +motor.cogging_dq_comp.296 0 +motor.cogging_dq_comp.297 0 +motor.cogging_dq_comp.298 0 +motor.cogging_dq_comp.299 0 +motor.cogging_dq_comp.300 0 +motor.cogging_dq_comp.301 0 +motor.cogging_dq_comp.302 0 +motor.cogging_dq_comp.303 0 +motor.cogging_dq_comp.304 0 +motor.cogging_dq_comp.305 0 +motor.cogging_dq_comp.306 0 +motor.cogging_dq_comp.307 0 +motor.cogging_dq_comp.308 0 +motor.cogging_dq_comp.309 0 +motor.cogging_dq_comp.310 0 +motor.cogging_dq_comp.311 0 +motor.cogging_dq_comp.312 0 +motor.cogging_dq_comp.313 0 +motor.cogging_dq_comp.314 0 +motor.cogging_dq_comp.315 0 +motor.cogging_dq_comp.316 0 +motor.cogging_dq_comp.317 0 +motor.cogging_dq_comp.318 0 +motor.cogging_dq_comp.319 0 +motor.cogging_dq_comp.320 0 +motor.cogging_dq_comp.321 0 +motor.cogging_dq_comp.322 0 +motor.cogging_dq_comp.323 0 +motor.cogging_dq_comp.324 0 +motor.cogging_dq_comp.325 0 +motor.cogging_dq_comp.326 0 +motor.cogging_dq_comp.327 0 +motor.cogging_dq_comp.328 0 +motor.cogging_dq_comp.329 0 +motor.cogging_dq_comp.330 0 +motor.cogging_dq_comp.331 0 +motor.cogging_dq_comp.332 0 +motor.cogging_dq_comp.333 0 +motor.cogging_dq_comp.334 0 +motor.cogging_dq_comp.335 0 +motor.cogging_dq_comp.336 0 +motor.cogging_dq_comp.337 0 +motor.cogging_dq_comp.338 0 +motor.cogging_dq_comp.339 0 +motor.cogging_dq_comp.340 0 +motor.cogging_dq_comp.341 0 +motor.cogging_dq_comp.342 0 +motor.cogging_dq_comp.343 0 +motor.cogging_dq_comp.344 0 +motor.cogging_dq_comp.345 0 +motor.cogging_dq_comp.346 0 +motor.cogging_dq_comp.347 0 +motor.cogging_dq_comp.348 0 +motor.cogging_dq_comp.349 0 +motor.cogging_dq_comp.350 0 +motor.cogging_dq_comp.351 0 +motor.cogging_dq_comp.352 0 +motor.cogging_dq_comp.353 0 +motor.cogging_dq_comp.354 0 +motor.cogging_dq_comp.355 0 +motor.cogging_dq_comp.356 0 +motor.cogging_dq_comp.357 0 +motor.cogging_dq_comp.358 0 +motor.cogging_dq_comp.359 0 +motor.cogging_dq_comp.360 0 +motor.cogging_dq_comp.361 0 +motor.cogging_dq_comp.362 0 +motor.cogging_dq_comp.363 0 +motor.cogging_dq_comp.364 0 +motor.cogging_dq_comp.365 0 +motor.cogging_dq_comp.366 0 +motor.cogging_dq_comp.367 0 +motor.cogging_dq_comp.368 0 +motor.cogging_dq_comp.369 0 +motor.cogging_dq_comp.370 0 +motor.cogging_dq_comp.371 0 +motor.cogging_dq_comp.372 0 +motor.cogging_dq_comp.373 0 +motor.cogging_dq_comp.374 0 +motor.cogging_dq_comp.375 0 +motor.cogging_dq_comp.376 0 +motor.cogging_dq_comp.377 0 +motor.cogging_dq_comp.378 0 +motor.cogging_dq_comp.379 0 +motor.cogging_dq_comp.380 0 +motor.cogging_dq_comp.381 0 +motor.cogging_dq_comp.382 0 +motor.cogging_dq_comp.383 0 +motor.cogging_dq_comp.384 0 +motor.cogging_dq_comp.385 0 +motor.cogging_dq_comp.386 0 +motor.cogging_dq_comp.387 0 +motor.cogging_dq_comp.388 0 +motor.cogging_dq_comp.389 0 +motor.cogging_dq_comp.390 0 +motor.cogging_dq_comp.391 0 +motor.cogging_dq_comp.392 0 +motor.cogging_dq_comp.393 0 +motor.cogging_dq_comp.394 0 +motor.cogging_dq_comp.395 0 +motor.cogging_dq_comp.396 0 +motor.cogging_dq_comp.397 0 +motor.cogging_dq_comp.398 0 +motor.cogging_dq_comp.399 0 +motor.cogging_dq_comp.400 0 +motor.cogging_dq_comp.401 0 +motor.cogging_dq_comp.402 0 +motor.cogging_dq_comp.403 0 +motor.cogging_dq_comp.404 0 +motor.cogging_dq_comp.405 0 +motor.cogging_dq_comp.406 0 +motor.cogging_dq_comp.407 0 +motor.cogging_dq_comp.408 0 +motor.cogging_dq_comp.409 0 +motor.cogging_dq_comp.410 0 +motor.cogging_dq_comp.411 0 +motor.cogging_dq_comp.412 0 +motor.cogging_dq_comp.413 0 +motor.cogging_dq_comp.414 0 +motor.cogging_dq_comp.415 0 +motor.cogging_dq_comp.416 0 +motor.cogging_dq_comp.417 0 +motor.cogging_dq_comp.418 0 +motor.cogging_dq_comp.419 0 +motor.cogging_dq_comp.420 0 +motor.cogging_dq_comp.421 0 +motor.cogging_dq_comp.422 0 +motor.cogging_dq_comp.423 0 +motor.cogging_dq_comp.424 0 +motor.cogging_dq_comp.425 0 +motor.cogging_dq_comp.426 0 +motor.cogging_dq_comp.427 0 +motor.cogging_dq_comp.428 0 +motor.cogging_dq_comp.429 0 +motor.cogging_dq_comp.430 0 +motor.cogging_dq_comp.431 0 +motor.cogging_dq_comp.432 0 +motor.cogging_dq_comp.433 0 +motor.cogging_dq_comp.434 0 +motor.cogging_dq_comp.435 0 +motor.cogging_dq_comp.436 0 +motor.cogging_dq_comp.437 0 +motor.cogging_dq_comp.438 0 +motor.cogging_dq_comp.439 0 +motor.cogging_dq_comp.440 0 +motor.cogging_dq_comp.441 0 +motor.cogging_dq_comp.442 0 +motor.cogging_dq_comp.443 0 +motor.cogging_dq_comp.444 0 +motor.cogging_dq_comp.445 0 +motor.cogging_dq_comp.446 0 +motor.cogging_dq_comp.447 0 +motor.cogging_dq_comp.448 0 +motor.cogging_dq_comp.449 0 +motor.cogging_dq_comp.450 0 +motor.cogging_dq_comp.451 0 +motor.cogging_dq_comp.452 0 +motor.cogging_dq_comp.453 0 +motor.cogging_dq_comp.454 0 +motor.cogging_dq_comp.455 0 +motor.cogging_dq_comp.456 0 +motor.cogging_dq_comp.457 0 +motor.cogging_dq_comp.458 0 +motor.cogging_dq_comp.459 0 +motor.cogging_dq_comp.460 0 +motor.cogging_dq_comp.461 0 +motor.cogging_dq_comp.462 0 +motor.cogging_dq_comp.463 0 +motor.cogging_dq_comp.464 0 +motor.cogging_dq_comp.465 0 +motor.cogging_dq_comp.466 0 +motor.cogging_dq_comp.467 0 +motor.cogging_dq_comp.468 0 +motor.cogging_dq_comp.469 0 +motor.cogging_dq_comp.470 0 +motor.cogging_dq_comp.471 0 +motor.cogging_dq_comp.472 0 +motor.cogging_dq_comp.473 0 +motor.cogging_dq_comp.474 0 +motor.cogging_dq_comp.475 0 +motor.cogging_dq_comp.476 0 +motor.cogging_dq_comp.477 0 +motor.cogging_dq_comp.478 0 +motor.cogging_dq_comp.479 0 +motor.cogging_dq_comp.480 0 +motor.cogging_dq_comp.481 0 +motor.cogging_dq_comp.482 0 +motor.cogging_dq_comp.483 0 +motor.cogging_dq_comp.484 0 +motor.cogging_dq_comp.485 0 +motor.cogging_dq_comp.486 0 +motor.cogging_dq_comp.487 0 +motor.cogging_dq_comp.488 0 +motor.cogging_dq_comp.489 0 +motor.cogging_dq_comp.490 0 +motor.cogging_dq_comp.491 0 +motor.cogging_dq_comp.492 0 +motor.cogging_dq_comp.493 0 +motor.cogging_dq_comp.494 0 +motor.cogging_dq_comp.495 0 +motor.cogging_dq_comp.496 0 +motor.cogging_dq_comp.497 0 +motor.cogging_dq_comp.498 0 +motor.cogging_dq_comp.499 0 +motor.cogging_dq_comp.500 0 +motor.cogging_dq_comp.501 0 +motor.cogging_dq_comp.502 0 +motor.cogging_dq_comp.503 0 +motor.cogging_dq_comp.504 0 +motor.cogging_dq_comp.505 0 +motor.cogging_dq_comp.506 0 +motor.cogging_dq_comp.507 0 +motor.cogging_dq_comp.508 0 +motor.cogging_dq_comp.509 0 +motor.cogging_dq_comp.510 0 +motor.cogging_dq_comp.511 0 +motor.cogging_dq_comp.512 0 +motor.cogging_dq_comp.513 0 +motor.cogging_dq_comp.514 0 +motor.cogging_dq_comp.515 0 +motor.cogging_dq_comp.516 0 +motor.cogging_dq_comp.517 0 +motor.cogging_dq_comp.518 0 +motor.cogging_dq_comp.519 0 +motor.cogging_dq_comp.520 0 +motor.cogging_dq_comp.521 0 +motor.cogging_dq_comp.522 0 +motor.cogging_dq_comp.523 0 +motor.cogging_dq_comp.524 0 +motor.cogging_dq_comp.525 0 +motor.cogging_dq_comp.526 0 +motor.cogging_dq_comp.527 0 +motor.cogging_dq_comp.528 0 +motor.cogging_dq_comp.529 0 +motor.cogging_dq_comp.530 0 +motor.cogging_dq_comp.531 0 +motor.cogging_dq_comp.532 0 +motor.cogging_dq_comp.533 0 +motor.cogging_dq_comp.534 0 +motor.cogging_dq_comp.535 0 +motor.cogging_dq_comp.536 0 +motor.cogging_dq_comp.537 0 +motor.cogging_dq_comp.538 0 +motor.cogging_dq_comp.539 0 +motor.cogging_dq_comp.540 0 +motor.cogging_dq_comp.541 0 +motor.cogging_dq_comp.542 0 +motor.cogging_dq_comp.543 0 +motor.cogging_dq_comp.544 0 +motor.cogging_dq_comp.545 0 +motor.cogging_dq_comp.546 0 +motor.cogging_dq_comp.547 0 +motor.cogging_dq_comp.548 0 +motor.cogging_dq_comp.549 0 +motor.cogging_dq_comp.550 0 +motor.cogging_dq_comp.551 0 +motor.cogging_dq_comp.552 0 +motor.cogging_dq_comp.553 0 +motor.cogging_dq_comp.554 0 +motor.cogging_dq_comp.555 0 +motor.cogging_dq_comp.556 0 +motor.cogging_dq_comp.557 0 +motor.cogging_dq_comp.558 0 +motor.cogging_dq_comp.559 0 +motor.cogging_dq_comp.560 0 +motor.cogging_dq_comp.561 0 +motor.cogging_dq_comp.562 0 +motor.cogging_dq_comp.563 0 +motor.cogging_dq_comp.564 0 +motor.cogging_dq_comp.565 0 +motor.cogging_dq_comp.566 0 +motor.cogging_dq_comp.567 0 +motor.cogging_dq_comp.568 0 +motor.cogging_dq_comp.569 0 +motor.cogging_dq_comp.570 0 +motor.cogging_dq_comp.571 0 +motor.cogging_dq_comp.572 0 +motor.cogging_dq_comp.573 0 +motor.cogging_dq_comp.574 0 +motor.cogging_dq_comp.575 0 +motor.cogging_dq_comp.576 0 +motor.cogging_dq_comp.577 0 +motor.cogging_dq_comp.578 0 +motor.cogging_dq_comp.579 0 +motor.cogging_dq_comp.580 0 +motor.cogging_dq_comp.581 0 +motor.cogging_dq_comp.582 0 +motor.cogging_dq_comp.583 0 +motor.cogging_dq_comp.584 0 +motor.cogging_dq_comp.585 0 +motor.cogging_dq_comp.586 0 +motor.cogging_dq_comp.587 0 +motor.cogging_dq_comp.588 0 +motor.cogging_dq_comp.589 0 +motor.cogging_dq_comp.590 0 +motor.cogging_dq_comp.591 0 +motor.cogging_dq_comp.592 0 +motor.cogging_dq_comp.593 0 +motor.cogging_dq_comp.594 0 +motor.cogging_dq_comp.595 0 +motor.cogging_dq_comp.596 0 +motor.cogging_dq_comp.597 0 +motor.cogging_dq_comp.598 0 +motor.cogging_dq_comp.599 0 +motor.cogging_dq_comp.600 0 +motor.cogging_dq_comp.601 0 +motor.cogging_dq_comp.602 0 +motor.cogging_dq_comp.603 0 +motor.cogging_dq_comp.604 0 +motor.cogging_dq_comp.605 0 +motor.cogging_dq_comp.606 0 +motor.cogging_dq_comp.607 0 +motor.cogging_dq_comp.608 0 +motor.cogging_dq_comp.609 0 +motor.cogging_dq_comp.610 0 +motor.cogging_dq_comp.611 0 +motor.cogging_dq_comp.612 0 +motor.cogging_dq_comp.613 0 +motor.cogging_dq_comp.614 0 +motor.cogging_dq_comp.615 0 +motor.cogging_dq_comp.616 0 +motor.cogging_dq_comp.617 0 +motor.cogging_dq_comp.618 0 +motor.cogging_dq_comp.619 0 +motor.cogging_dq_comp.620 0 +motor.cogging_dq_comp.621 0 +motor.cogging_dq_comp.622 0 +motor.cogging_dq_comp.623 0 +motor.cogging_dq_comp.624 0 +motor.cogging_dq_comp.625 0 +motor.cogging_dq_comp.626 0 +motor.cogging_dq_comp.627 0 +motor.cogging_dq_comp.628 0 +motor.cogging_dq_comp.629 0 +motor.cogging_dq_comp.630 0 +motor.cogging_dq_comp.631 0 +motor.cogging_dq_comp.632 0 +motor.cogging_dq_comp.633 0 +motor.cogging_dq_comp.634 0 +motor.cogging_dq_comp.635 0 +motor.cogging_dq_comp.636 0 +motor.cogging_dq_comp.637 0 +motor.cogging_dq_comp.638 0 +motor.cogging_dq_comp.639 0 +motor.cogging_dq_comp.640 0 +motor.cogging_dq_comp.641 0 +motor.cogging_dq_comp.642 0 +motor.cogging_dq_comp.643 0 +motor.cogging_dq_comp.644 0 +motor.cogging_dq_comp.645 0 +motor.cogging_dq_comp.646 0 +motor.cogging_dq_comp.647 0 +motor.cogging_dq_comp.648 0 +motor.cogging_dq_comp.649 0 +motor.cogging_dq_comp.650 0 +motor.cogging_dq_comp.651 0 +motor.cogging_dq_comp.652 0 +motor.cogging_dq_comp.653 0 +motor.cogging_dq_comp.654 0 +motor.cogging_dq_comp.655 0 +motor.cogging_dq_comp.656 0 +motor.cogging_dq_comp.657 0 +motor.cogging_dq_comp.658 0 +motor.cogging_dq_comp.659 0 +motor.cogging_dq_comp.660 0 +motor.cogging_dq_comp.661 0 +motor.cogging_dq_comp.662 0 +motor.cogging_dq_comp.663 0 +motor.cogging_dq_comp.664 0 +motor.cogging_dq_comp.665 0 +motor.cogging_dq_comp.666 0 +motor.cogging_dq_comp.667 0 +motor.cogging_dq_comp.668 0 +motor.cogging_dq_comp.669 0 +motor.cogging_dq_comp.670 0 +motor.cogging_dq_comp.671 0 +motor.cogging_dq_comp.672 0 +motor.cogging_dq_comp.673 0 +motor.cogging_dq_comp.674 0 +motor.cogging_dq_comp.675 0 +motor.cogging_dq_comp.676 0 +motor.cogging_dq_comp.677 0 +motor.cogging_dq_comp.678 0 +motor.cogging_dq_comp.679 0 +motor.cogging_dq_comp.680 0 +motor.cogging_dq_comp.681 0 +motor.cogging_dq_comp.682 0 +motor.cogging_dq_comp.683 0 +motor.cogging_dq_comp.684 0 +motor.cogging_dq_comp.685 0 +motor.cogging_dq_comp.686 0 +motor.cogging_dq_comp.687 0 +motor.cogging_dq_comp.688 0 +motor.cogging_dq_comp.689 0 +motor.cogging_dq_comp.690 0 +motor.cogging_dq_comp.691 0 +motor.cogging_dq_comp.692 0 +motor.cogging_dq_comp.693 0 +motor.cogging_dq_comp.694 0 +motor.cogging_dq_comp.695 0 +motor.cogging_dq_comp.696 0 +motor.cogging_dq_comp.697 0 +motor.cogging_dq_comp.698 0 +motor.cogging_dq_comp.699 0 +motor.cogging_dq_comp.700 0 +motor.cogging_dq_comp.701 0 +motor.cogging_dq_comp.702 0 +motor.cogging_dq_comp.703 0 +motor.cogging_dq_comp.704 0 +motor.cogging_dq_comp.705 0 +motor.cogging_dq_comp.706 0 +motor.cogging_dq_comp.707 0 +motor.cogging_dq_comp.708 0 +motor.cogging_dq_comp.709 0 +motor.cogging_dq_comp.710 0 +motor.cogging_dq_comp.711 0 +motor.cogging_dq_comp.712 0 +motor.cogging_dq_comp.713 0 +motor.cogging_dq_comp.714 0 +motor.cogging_dq_comp.715 0 +motor.cogging_dq_comp.716 0 +motor.cogging_dq_comp.717 0 +motor.cogging_dq_comp.718 0 +motor.cogging_dq_comp.719 0 +motor.cogging_dq_comp.720 0 +motor.cogging_dq_comp.721 0 +motor.cogging_dq_comp.722 0 +motor.cogging_dq_comp.723 0 +motor.cogging_dq_comp.724 0 +motor.cogging_dq_comp.725 0 +motor.cogging_dq_comp.726 0 +motor.cogging_dq_comp.727 0 +motor.cogging_dq_comp.728 0 +motor.cogging_dq_comp.729 0 +motor.cogging_dq_comp.730 0 +motor.cogging_dq_comp.731 0 +motor.cogging_dq_comp.732 0 +motor.cogging_dq_comp.733 0 +motor.cogging_dq_comp.734 0 +motor.cogging_dq_comp.735 0 +motor.cogging_dq_comp.736 0 +motor.cogging_dq_comp.737 0 +motor.cogging_dq_comp.738 0 +motor.cogging_dq_comp.739 0 +motor.cogging_dq_comp.740 0 +motor.cogging_dq_comp.741 0 +motor.cogging_dq_comp.742 0 +motor.cogging_dq_comp.743 0 +motor.cogging_dq_comp.744 0 +motor.cogging_dq_comp.745 0 +motor.cogging_dq_comp.746 0 +motor.cogging_dq_comp.747 0 +motor.cogging_dq_comp.748 0 +motor.cogging_dq_comp.749 0 +motor.cogging_dq_comp.750 0 +motor.cogging_dq_comp.751 0 +motor.cogging_dq_comp.752 0 +motor.cogging_dq_comp.753 0 +motor.cogging_dq_comp.754 0 +motor.cogging_dq_comp.755 0 +motor.cogging_dq_comp.756 0 +motor.cogging_dq_comp.757 0 +motor.cogging_dq_comp.758 0 +motor.cogging_dq_comp.759 0 +motor.cogging_dq_comp.760 0 +motor.cogging_dq_comp.761 0 +motor.cogging_dq_comp.762 0 +motor.cogging_dq_comp.763 0 +motor.cogging_dq_comp.764 0 +motor.cogging_dq_comp.765 0 +motor.cogging_dq_comp.766 0 +motor.cogging_dq_comp.767 0 +motor.cogging_dq_comp.768 0 +motor.cogging_dq_comp.769 0 +motor.cogging_dq_comp.770 0 +motor.cogging_dq_comp.771 0 +motor.cogging_dq_comp.772 0 +motor.cogging_dq_comp.773 0 +motor.cogging_dq_comp.774 0 +motor.cogging_dq_comp.775 0 +motor.cogging_dq_comp.776 0 +motor.cogging_dq_comp.777 0 +motor.cogging_dq_comp.778 0 +motor.cogging_dq_comp.779 0 +motor.cogging_dq_comp.780 0 +motor.cogging_dq_comp.781 0 +motor.cogging_dq_comp.782 0 +motor.cogging_dq_comp.783 0 +motor.cogging_dq_comp.784 0 +motor.cogging_dq_comp.785 0 +motor.cogging_dq_comp.786 0 +motor.cogging_dq_comp.787 0 +motor.cogging_dq_comp.788 0 +motor.cogging_dq_comp.789 0 +motor.cogging_dq_comp.790 0 +motor.cogging_dq_comp.791 0 +motor.cogging_dq_comp.792 0 +motor.cogging_dq_comp.793 0 +motor.cogging_dq_comp.794 0 +motor.cogging_dq_comp.795 0 +motor.cogging_dq_comp.796 0 +motor.cogging_dq_comp.797 0 +motor.cogging_dq_comp.798 0 +motor.cogging_dq_comp.799 0 +motor.cogging_dq_comp.800 0 +motor.cogging_dq_comp.801 0 +motor.cogging_dq_comp.802 0 +motor.cogging_dq_comp.803 0 +motor.cogging_dq_comp.804 0 +motor.cogging_dq_comp.805 0 +motor.cogging_dq_comp.806 0 +motor.cogging_dq_comp.807 0 +motor.cogging_dq_comp.808 0 +motor.cogging_dq_comp.809 0 +motor.cogging_dq_comp.810 0 +motor.cogging_dq_comp.811 0 +motor.cogging_dq_comp.812 0 +motor.cogging_dq_comp.813 0 +motor.cogging_dq_comp.814 0 +motor.cogging_dq_comp.815 0 +motor.cogging_dq_comp.816 0 +motor.cogging_dq_comp.817 0 +motor.cogging_dq_comp.818 0 +motor.cogging_dq_comp.819 0 +motor.cogging_dq_comp.820 0 +motor.cogging_dq_comp.821 0 +motor.cogging_dq_comp.822 0 +motor.cogging_dq_comp.823 0 +motor.cogging_dq_comp.824 0 +motor.cogging_dq_comp.825 0 +motor.cogging_dq_comp.826 0 +motor.cogging_dq_comp.827 0 +motor.cogging_dq_comp.828 0 +motor.cogging_dq_comp.829 0 +motor.cogging_dq_comp.830 0 +motor.cogging_dq_comp.831 0 +motor.cogging_dq_comp.832 0 +motor.cogging_dq_comp.833 0 +motor.cogging_dq_comp.834 0 +motor.cogging_dq_comp.835 0 +motor.cogging_dq_comp.836 0 +motor.cogging_dq_comp.837 0 +motor.cogging_dq_comp.838 0 +motor.cogging_dq_comp.839 0 +motor.cogging_dq_comp.840 0 +motor.cogging_dq_comp.841 0 +motor.cogging_dq_comp.842 0 +motor.cogging_dq_comp.843 0 +motor.cogging_dq_comp.844 0 +motor.cogging_dq_comp.845 0 +motor.cogging_dq_comp.846 0 +motor.cogging_dq_comp.847 0 +motor.cogging_dq_comp.848 0 +motor.cogging_dq_comp.849 0 +motor.cogging_dq_comp.850 0 +motor.cogging_dq_comp.851 0 +motor.cogging_dq_comp.852 0 +motor.cogging_dq_comp.853 0 +motor.cogging_dq_comp.854 0 +motor.cogging_dq_comp.855 0 +motor.cogging_dq_comp.856 0 +motor.cogging_dq_comp.857 0 +motor.cogging_dq_comp.858 0 +motor.cogging_dq_comp.859 0 +motor.cogging_dq_comp.860 0 +motor.cogging_dq_comp.861 0 +motor.cogging_dq_comp.862 0 +motor.cogging_dq_comp.863 0 +motor.cogging_dq_comp.864 0 +motor.cogging_dq_comp.865 0 +motor.cogging_dq_comp.866 0 +motor.cogging_dq_comp.867 0 +motor.cogging_dq_comp.868 0 +motor.cogging_dq_comp.869 0 +motor.cogging_dq_comp.870 0 +motor.cogging_dq_comp.871 0 +motor.cogging_dq_comp.872 0 +motor.cogging_dq_comp.873 0 +motor.cogging_dq_comp.874 0 +motor.cogging_dq_comp.875 0 +motor.cogging_dq_comp.876 0 +motor.cogging_dq_comp.877 0 +motor.cogging_dq_comp.878 0 +motor.cogging_dq_comp.879 0 +motor.cogging_dq_comp.880 0 +motor.cogging_dq_comp.881 0 +motor.cogging_dq_comp.882 0 +motor.cogging_dq_comp.883 0 +motor.cogging_dq_comp.884 0 +motor.cogging_dq_comp.885 0 +motor.cogging_dq_comp.886 0 +motor.cogging_dq_comp.887 0 +motor.cogging_dq_comp.888 0 +motor.cogging_dq_comp.889 0 +motor.cogging_dq_comp.890 0 +motor.cogging_dq_comp.891 0 +motor.cogging_dq_comp.892 0 +motor.cogging_dq_comp.893 0 +motor.cogging_dq_comp.894 0 +motor.cogging_dq_comp.895 0 +motor.cogging_dq_comp.896 0 +motor.cogging_dq_comp.897 0 +motor.cogging_dq_comp.898 0 +motor.cogging_dq_comp.899 0 +motor.cogging_dq_comp.900 0 +motor.cogging_dq_comp.901 0 +motor.cogging_dq_comp.902 0 +motor.cogging_dq_comp.903 0 +motor.cogging_dq_comp.904 0 +motor.cogging_dq_comp.905 0 +motor.cogging_dq_comp.906 0 +motor.cogging_dq_comp.907 0 +motor.cogging_dq_comp.908 0 +motor.cogging_dq_comp.909 0 +motor.cogging_dq_comp.910 0 +motor.cogging_dq_comp.911 0 +motor.cogging_dq_comp.912 0 +motor.cogging_dq_comp.913 0 +motor.cogging_dq_comp.914 0 +motor.cogging_dq_comp.915 0 +motor.cogging_dq_comp.916 0 +motor.cogging_dq_comp.917 0 +motor.cogging_dq_comp.918 0 +motor.cogging_dq_comp.919 0 +motor.cogging_dq_comp.920 0 +motor.cogging_dq_comp.921 0 +motor.cogging_dq_comp.922 0 +motor.cogging_dq_comp.923 0 +motor.cogging_dq_comp.924 0 +motor.cogging_dq_comp.925 0 +motor.cogging_dq_comp.926 0 +motor.cogging_dq_comp.927 0 +motor.cogging_dq_comp.928 0 +motor.cogging_dq_comp.929 0 +motor.cogging_dq_comp.930 0 +motor.cogging_dq_comp.931 0 +motor.cogging_dq_comp.932 0 +motor.cogging_dq_comp.933 0 +motor.cogging_dq_comp.934 0 +motor.cogging_dq_comp.935 0 +motor.cogging_dq_comp.936 0 +motor.cogging_dq_comp.937 0 +motor.cogging_dq_comp.938 0 +motor.cogging_dq_comp.939 0 +motor.cogging_dq_comp.940 0 +motor.cogging_dq_comp.941 0 +motor.cogging_dq_comp.942 0 +motor.cogging_dq_comp.943 0 +motor.cogging_dq_comp.944 0 +motor.cogging_dq_comp.945 0 +motor.cogging_dq_comp.946 0 +motor.cogging_dq_comp.947 0 +motor.cogging_dq_comp.948 0 +motor.cogging_dq_comp.949 0 +motor.cogging_dq_comp.950 0 +motor.cogging_dq_comp.951 0 +motor.cogging_dq_comp.952 0 +motor.cogging_dq_comp.953 0 +motor.cogging_dq_comp.954 0 +motor.cogging_dq_comp.955 0 +motor.cogging_dq_comp.956 0 +motor.cogging_dq_comp.957 0 +motor.cogging_dq_comp.958 0 +motor.cogging_dq_comp.959 0 +motor.cogging_dq_comp.960 0 +motor.cogging_dq_comp.961 0 +motor.cogging_dq_comp.962 0 +motor.cogging_dq_comp.963 0 +motor.cogging_dq_comp.964 0 +motor.cogging_dq_comp.965 0 +motor.cogging_dq_comp.966 0 +motor.cogging_dq_comp.967 0 +motor.cogging_dq_comp.968 0 +motor.cogging_dq_comp.969 0 +motor.cogging_dq_comp.970 0 +motor.cogging_dq_comp.971 0 +motor.cogging_dq_comp.972 0 +motor.cogging_dq_comp.973 0 +motor.cogging_dq_comp.974 0 +motor.cogging_dq_comp.975 0 +motor.cogging_dq_comp.976 0 +motor.cogging_dq_comp.977 0 +motor.cogging_dq_comp.978 0 +motor.cogging_dq_comp.979 0 +motor.cogging_dq_comp.980 0 +motor.cogging_dq_comp.981 0 +motor.cogging_dq_comp.982 0 +motor.cogging_dq_comp.983 0 +motor.cogging_dq_comp.984 0 +motor.cogging_dq_comp.985 0 +motor.cogging_dq_comp.986 0 +motor.cogging_dq_comp.987 0 +motor.cogging_dq_comp.988 0 +motor.cogging_dq_comp.989 0 +motor.cogging_dq_comp.990 0 +motor.cogging_dq_comp.991 0 +motor.cogging_dq_comp.992 0 +motor.cogging_dq_comp.993 0 +motor.cogging_dq_comp.994 0 +motor.cogging_dq_comp.995 0 +motor.cogging_dq_comp.996 0 +motor.cogging_dq_comp.997 0 +motor.cogging_dq_comp.998 0 +motor.cogging_dq_comp.999 0 +motor.cogging_dq_comp.1000 0 +motor.cogging_dq_comp.1001 0 +motor.cogging_dq_comp.1002 0 +motor.cogging_dq_comp.1003 0 +motor.cogging_dq_comp.1004 0 +motor.cogging_dq_comp.1005 0 +motor.cogging_dq_comp.1006 0 +motor.cogging_dq_comp.1007 0 +motor.cogging_dq_comp.1008 0 +motor.cogging_dq_comp.1009 0 +motor.cogging_dq_comp.1010 0 +motor.cogging_dq_comp.1011 0 +motor.cogging_dq_comp.1012 0 +motor.cogging_dq_comp.1013 0 +motor.cogging_dq_comp.1014 0 +motor.cogging_dq_comp.1015 0 +motor.cogging_dq_comp.1016 0 +motor.cogging_dq_comp.1017 0 +motor.cogging_dq_comp.1018 0 +motor.cogging_dq_comp.1019 0 +motor.cogging_dq_comp.1020 0 +motor.cogging_dq_comp.1021 0 +motor.cogging_dq_comp.1022 0 +motor.cogging_dq_comp.1023 0 +drv8323_conf.dis_cpuv 0 +drv8323_conf.dis_gdf 0 +drv8323_conf.otw_rep 0 +drv8323_conf.pwm_mode 1 +drv8323_conf.pwm_1x_asynchronous 0 +drv8323_conf.pwm_1x_dir 0 +drv8323_conf.idrivep_hs_ma 100 +drv8323_conf.idriven_hs_ma 200 +drv8323_conf.cbc 1 +drv8323_conf.tdrive_ns 1000 +drv8323_conf.idrivep_ls_ma 100 +drv8323_conf.idriven_ls_ma 200 +drv8323_conf.tretry 0 +drv8323_conf.dead_time_ns 50 +drv8323_conf.ocp_mode 0 +drv8323_conf.ocp_deg_us 4 +drv8323_conf.vds_lvl_mv 700 +drv8323_conf.csa_fet 0 +drv8323_conf.vref_div 1 +drv8323_conf.ls_ref 0 +drv8323_conf.csa_gain 20 +drv8323_conf.dis_sen 0 +drv8323_conf.sen_lvl_mv 500 +servo.pwm_rate_hz 30000 +servo.i_gain 20.000000 +servo.current_sense_ohm 0.000500 +servo.pwm_comp_off 0.027000 +servo.pwm_comp_mag 0.005000 +servo.pwm_scale 1.000000 +servo.max_voltage 46.000000 +servo.max_power_W 450.000000 +servo.derate_temperature 50.000000 +servo.fault_temperature 75.000000 +servo.enable_motor_temperature 0 +servo.motor_derate_temperature 50.000000 +servo.motor_fault_temperature nan +servo.velocity_threshold 0.000000 +servo.position_derate 0.020000 +servo.adc_cur_cycles 2 +servo.adc_aux_cycles 47 +servo.pid_dq.kp 0.234858 +servo.pid_dq.ki 162.397873 +servo.pid_position.kp 0.500000 +servo.pid_position.ki 0.000000 +servo.pid_position.kd 0.050000 +servo.pid_position.iratelimit -1.000000 +servo.pid_position.ilimit 0.000000 +servo.pid_position.max_desired_rate 0.000000 +servo.pid_position.sign -1 +servo.current_feedforward 1.000000 +servo.bemf_feedforward 1.000000 +servo.default_velocity_limit nan +servo.default_accel_limit nan +servo.voltage_mode_control 0 +servo.fixed_voltage_mode 0 +servo.fixed_voltage_control_V 0.000000 +servo.max_position_slip 10.000000 +servo.default_timeout_s 0.100000 +servo.timeout_max_torque_Nm 5.000000 +servo.timeout_mode 12 +servo.flux_brake_min_voltage 43.500000 +servo.flux_brake_resistance_ohm 0.025000 +servo.max_current_A 7.500000 +servo.derate_current_A -20.000000 +servo.max_velocity 500.000000 +servo.max_velocity_derate 2.000000 +servo.cooldown_cycles 256 +servo.velocity_zero_capture_threshold 0.050000 +servo.emit_debug 0 +servopos.position_min nan +servopos.position_max nan +id.id 22 +can.prefix 0 + diff --git a/config/moteus/back_right.cfg b/config/moteus/back_right.cfg new file mode 100644 index 000000000..920c0382b --- /dev/null +++ b/config/moteus/back_right.cfg @@ -0,0 +1,350 @@ +motor.cogging_dq_comp.748 0 +motor.cogging_dq_comp.749 0 +motor.cogging_dq_comp.750 0 +motor.cogging_dq_comp.751 0 +motor.cogging_dq_comp.752 0 +motor.cogging_dq_comp.753 0 +motor.cogging_dq_comp.754 0 +motor.cogging_dq_comp.755 0 +motor.cogging_dq_comp.756 0 +motor.cogging_dq_comp.757 0 +motor.cogging_dq_comp.758 0 +motor.cogging_dq_comp.759 0 +motor.cogging_dq_comp.760 0 +motor.cogging_dq_comp.761 0 +motor.cogging_dq_comp.762 0 +motor.cogging_dq_comp.763 0 +motor.cogging_dq_comp.764 0 +motor.cogging_dq_comp.765 0 +motor.cogging_dq_comp.766 0 +motor.cogging_dq_comp.767 0 +motor.cogging_dq_comp.768 0 +motor.cogging_dq_comp.769 0 +motor.cogging_dq_comp.770 0 +motor.cogging_dq_comp.771 0 +motor.cogging_dq_comp.772 0 +motor.cogging_dq_comp.773 0 +motor.cogging_dq_comp.774 0 +motor.cogging_dq_comp.775 0 +motor.cogging_dq_comp.776 0 +motor.cogging_dq_comp.777 0 +motor.cogging_dq_comp.778 0 +motor.cogging_dq_comp.779 0 +motor.cogging_dq_comp.780 0 +motor.cogging_dq_comp.781 0 +motor.cogging_dq_comp.782 0 +motor.cogging_dq_comp.783 0 +motor.cogging_dq_comp.784 0 +motor.cogging_dq_comp.785 0 +motor.cogging_dq_comp.786 0 +motor.cogging_dq_comp.787 0 +motor.cogging_dq_comp.788 0 +motor.cogging_dq_comp.789 0 +motor.cogging_dq_comp.790 0 +motor.cogging_dq_comp.791 0 +motor.cogging_dq_comp.792 0 +motor.cogging_dq_comp.793 0 +motor.cogging_dq_comp.794 0 +motor.cogging_dq_comp.795 0 +motor.cogging_dq_comp.796 0 +motor.cogging_dq_comp.797 0 +motor.cogging_dq_comp.798 0 +motor.cogging_dq_comp.799 0 +motor.cogging_dq_comp.800 0 +motor.cogging_dq_comp.801 0 +motor.cogging_dq_comp.802 0 +motor.cogging_dq_comp.803 0 +motor.cogging_dq_comp.804 0 +motor.cogging_dq_comp.805 0 +motor.cogging_dq_comp.806 0 +motor.cogging_dq_comp.807 0 +motor.cogging_dq_comp.808 0 +motor.cogging_dq_comp.809 0 +motor.cogging_dq_comp.810 0 +motor.cogging_dq_comp.811 0 +motor.cogging_dq_comp.812 0 +motor.cogging_dq_comp.813 0 +motor.cogging_dq_comp.814 0 +motor.cogging_dq_comp.815 0 +motor.cogging_dq_comp.816 0 +motor.cogging_dq_comp.817 0 +motor.cogging_dq_comp.818 0 +motor.cogging_dq_comp.819 0 +motor.cogging_dq_comp.820 0 +motor.cogging_dq_comp.821 0 +motor.cogging_dq_comp.822 0 +motor.cogging_dq_comp.823 0 +motor.cogging_dq_comp.824 0 +motor.cogging_dq_comp.825 0 +motor.cogging_dq_comp.826 0 +motor.cogging_dq_comp.827 0 +motor.cogging_dq_comp.828 0 +motor.cogging_dq_comp.829 0 +motor.cogging_dq_comp.830 0 +motor.cogging_dq_comp.831 0 +motor.cogging_dq_comp.832 0 +motor.cogging_dq_comp.833 0 +motor.cogging_dq_comp.834 0 +motor.cogging_dq_comp.835 0 +motor.cogging_dq_comp.836 0 +motor.cogging_dq_comp.837 0 +motor.cogging_dq_comp.838 0 +motor.cogging_dq_comp.839 0 +motor.cogging_dq_comp.840 0 +motor.cogging_dq_comp.841 0 +motor.cogging_dq_comp.842 0 +motor.cogging_dq_comp.843 0 +motor.cogging_dq_comp.844 0 +motor.cogging_dq_comp.845 0 +motor.cogging_dq_comp.846 0 +motor.cogging_dq_comp.847 0 +motor.cogging_dq_comp.848 0 +motor.cogging_dq_comp.849 0 +motor.cogging_dq_comp.850 0 +motor.cogging_dq_comp.851 0 +motor.cogging_dq_comp.852 0 +motor.cogging_dq_comp.853 0 +motor.cogging_dq_comp.854 0 +motor.cogging_dq_comp.855 0 +motor.cogging_dq_comp.856 0 +motor.cogging_dq_comp.857 0 +motor.cogging_dq_comp.858 0 +motor.cogging_dq_comp.859 0 +motor.cogging_dq_comp.860 0 +motor.cogging_dq_comp.861 0 +motor.cogging_dq_comp.862 0 +motor.cogging_dq_comp.863 0 +motor.cogging_dq_comp.864 0 +motor.cogging_dq_comp.865 0 +motor.cogging_dq_comp.866 0 +motor.cogging_dq_comp.867 0 +motor.cogging_dq_comp.868 0 +motor.cogging_dq_comp.869 0 +motor.cogging_dq_comp.870 0 +motor.cogging_dq_comp.871 0 +motor.cogging_dq_comp.872 0 +motor.cogging_dq_comp.873 0 +motor.cogging_dq_comp.874 0 +motor.cogging_dq_comp.875 0 +motor.cogging_dq_comp.876 0 +motor.cogging_dq_comp.877 0 +motor.cogging_dq_comp.878 0 +motor.cogging_dq_comp.879 0 +motor.cogging_dq_comp.880 0 +motor.cogging_dq_comp.881 0 +motor.cogging_dq_comp.882 0 +motor.cogging_dq_comp.883 0 +motor.cogging_dq_comp.884 0 +motor.cogging_dq_comp.885 0 +motor.cogging_dq_comp.886 0 +motor.cogging_dq_comp.887 0 +motor.cogging_dq_comp.888 0 +motor.cogging_dq_comp.889 0 +motor.cogging_dq_comp.890 0 +motor.cogging_dq_comp.891 0 +motor.cogging_dq_comp.892 0 +motor.cogging_dq_comp.893 0 +motor.cogging_dq_comp.894 0 +motor.cogging_dq_comp.895 0 +motor.cogging_dq_comp.896 0 +motor.cogging_dq_comp.897 0 +motor.cogging_dq_comp.898 0 +motor.cogging_dq_comp.899 0 +motor.cogging_dq_comp.900 0 +motor.cogging_dq_comp.901 0 +motor.cogging_dq_comp.902 0 +motor.cogging_dq_comp.903 0 +motor.cogging_dq_comp.904 0 +motor.cogging_dq_comp.905 0 +motor.cogging_dq_comp.906 0 +motor.cogging_dq_comp.907 0 +motor.cogging_dq_comp.908 0 +motor.cogging_dq_comp.909 0 +motor.cogging_dq_comp.910 0 +motor.cogging_dq_comp.911 0 +motor.cogging_dq_comp.912 0 +motor.cogging_dq_comp.913 0 +motor.cogging_dq_comp.914 0 +motor.cogging_dq_comp.915 0 +motor.cogging_dq_comp.916 0 +motor.cogging_dq_comp.917 0 +motor.cogging_dq_comp.918 0 +motor.cogging_dq_comp.919 0 +motor.cogging_dq_comp.920 0 +motor.cogging_dq_comp.921 0 +motor.cogging_dq_comp.922 0 +motor.cogging_dq_comp.923 0 +motor.cogging_dq_comp.924 0 +motor.cogging_dq_comp.925 0 +motor.cogging_dq_comp.926 0 +motor.cogging_dq_comp.927 0 +motor.cogging_dq_comp.928 0 +motor.cogging_dq_comp.929 0 +motor.cogging_dq_comp.930 0 +motor.cogging_dq_comp.931 0 +motor.cogging_dq_comp.932 0 +motor.cogging_dq_comp.933 0 +motor.cogging_dq_comp.934 0 +motor.cogging_dq_comp.935 0 +motor.cogging_dq_comp.936 0 +motor.cogging_dq_comp.937 0 +motor.cogging_dq_comp.938 0 +motor.cogging_dq_comp.939 0 +motor.cogging_dq_comp.940 0 +motor.cogging_dq_comp.941 0 +motor.cogging_dq_comp.942 0 +motor.cogging_dq_comp.943 0 +motor.cogging_dq_comp.944 0 +motor.cogging_dq_comp.945 0 +motor.cogging_dq_comp.946 0 +motor.cogging_dq_comp.947 0 +motor.cogging_dq_comp.948 0 +motor.cogging_dq_comp.949 0 +motor.cogging_dq_comp.950 0 +motor.cogging_dq_comp.951 0 +motor.cogging_dq_comp.952 0 +motor.cogging_dq_comp.953 0 +motor.cogging_dq_comp.954 0 +motor.cogging_dq_comp.955 0 +motor.cogging_dq_comp.956 0 +motor.cogging_dq_comp.957 0 +motor.cogging_dq_comp.958 0 +motor.cogging_dq_comp.959 0 +motor.cogging_dq_comp.960 0 +motor.cogging_dq_comp.961 0 +motor.cogging_dq_comp.962 0 +motor.cogging_dq_comp.963 0 +motor.cogging_dq_comp.964 0 +motor.cogging_dq_comp.965 0 +motor.cogging_dq_comp.966 0 +motor.cogging_dq_comp.967 0 +motor.cogging_dq_comp.968 0 +motor.cogging_dq_comp.969 0 +motor.cogging_dq_comp.970 0 +motor.cogging_dq_comp.971 0 +motor.cogging_dq_comp.972 0 +motor.cogging_dq_comp.973 0 +motor.cogging_dq_comp.974 0 +motor.cogging_dq_comp.975 0 +motor.cogging_dq_comp.976 0 +motor.cogging_dq_comp.977 0 +motor.cogging_dq_comp.978 0 +motor.cogging_dq_comp.979 0 +motor.cogging_dq_comp.980 0 +motor.cogging_dq_comp.981 0 +motor.cogging_dq_comp.982 0 +motor.cogging_dq_comp.983 0 +motor.cogging_dq_comp.984 0 +motor.cogging_dq_comp.985 0 +motor.cogging_dq_comp.986 0 +motor.cogging_dq_comp.987 0 +motor.cogging_dq_comp.988 0 +motor.cogging_dq_comp.989 0 +motor.cogging_dq_comp.990 0 +motor.cogging_dq_comp.991 0 +motor.cogging_dq_comp.992 0 +motor.cogging_dq_comp.993 0 +motor.cogging_dq_comp.994 0 +motor.cogging_dq_comp.995 0 +motor.cogging_dq_comp.996 0 +motor.cogging_dq_comp.997 0 +motor.cogging_dq_comp.998 0 +motor.cogging_dq_comp.999 0 +motor.cogging_dq_comp.1000 0 +motor.cogging_dq_comp.1001 0 +motor.cogging_dq_comp.1002 0 +motor.cogging_dq_comp.1003 0 +motor.cogging_dq_comp.1004 0 +motor.cogging_dq_comp.1005 0 +motor.cogging_dq_comp.1006 0 +motor.cogging_dq_comp.1007 0 +motor.cogging_dq_comp.1008 0 +motor.cogging_dq_comp.1009 0 +motor.cogging_dq_comp.1010 0 +motor.cogging_dq_comp.1011 0 +motor.cogging_dq_comp.1012 0 +motor.cogging_dq_comp.1013 0 +motor.cogging_dq_comp.1014 0 +motor.cogging_dq_comp.1015 0 +motor.cogging_dq_comp.1016 0 +motor.cogging_dq_comp.1017 0 +motor.cogging_dq_comp.1018 0 +motor.cogging_dq_comp.1019 0 +motor.cogging_dq_comp.1020 0 +motor.cogging_dq_comp.1021 0 +motor.cogging_dq_comp.1022 0 +motor.cogging_dq_comp.1023 0 +drv8323_conf.dis_cpuv 0 +drv8323_conf.dis_gdf 0 +drv8323_conf.otw_rep 0 +drv8323_conf.pwm_mode 1 +drv8323_conf.pwm_1x_asynchronous 0 +drv8323_conf.pwm_1x_dir 0 +drv8323_conf.idrivep_hs_ma 100 +drv8323_conf.idriven_hs_ma 200 +drv8323_conf.cbc 1 +drv8323_conf.tdrive_ns 1000 +drv8323_conf.idrivep_ls_ma 100 +drv8323_conf.idriven_ls_ma 200 +drv8323_conf.tretry 0 +drv8323_conf.dead_time_ns 50 +drv8323_conf.ocp_mode 0 +drv8323_conf.ocp_deg_us 4 +drv8323_conf.vds_lvl_mv 700 +drv8323_conf.csa_fet 0 +drv8323_conf.vref_div 1 +drv8323_conf.ls_ref 0 +drv8323_conf.csa_gain 20 +drv8323_conf.dis_sen 0 +drv8323_conf.sen_lvl_mv 500 +servo.pwm_rate_hz 30000 +servo.i_gain 20.000000 +servo.current_sense_ohm 0.000500 +servo.pwm_comp_off 0.027000 +servo.pwm_comp_mag 0.005000 +servo.pwm_scale 1.000000 +servo.max_voltage 46.000000 +servo.max_power_W 450.000000 +servo.derate_temperature 50.000000 +servo.fault_temperature 75.000000 +servo.enable_motor_temperature 0 +servo.motor_derate_temperature 50.000000 +servo.motor_fault_temperature nan +servo.velocity_threshold 0.000000 +servo.position_derate 0.020000 +servo.adc_cur_cycles 2 +servo.adc_aux_cycles 47 +servo.pid_dq.kp 0.200000 +servo.pid_dq.ki 157.382980 +servo.pid_position.kp 0.500000 +servo.pid_position.ki 0.000000 +servo.pid_position.kd 0.050000 +servo.pid_position.iratelimit -1.000000 +servo.pid_position.ilimit 0.000000 +servo.pid_position.max_desired_rate 0.000000 +servo.pid_position.sign -1 +servo.current_feedforward 1.000000 +servo.bemf_feedforward 1.000000 +servo.default_velocity_limit nan +servo.default_accel_limit nan +servo.voltage_mode_control 0 +servo.fixed_voltage_mode 0 +servo.fixed_voltage_control_V 0.000000 +servo.max_position_slip 10.000000 +servo.default_timeout_s 0.100000 +servo.timeout_max_torque_Nm 5.000000 +servo.timeout_mode 12 +servo.flux_brake_min_voltage 43.500000 +servo.flux_brake_resistance_ohm 0.025000 +servo.max_current_A 4.000000 +servo.derate_current_A -20.000000 +servo.max_velocity 500.000000 +servo.max_velocity_derate 2.000000 +servo.cooldown_cycles 256 +servo.velocity_zero_capture_threshold 0.050000 +servo.emit_debug 0 +servopos.position_min nan +servopos.position_max nan +id.id 21 +can.prefix 0 + diff --git a/config/moteus/front_left.cfg b/config/moteus/front_left.cfg new file mode 100644 index 000000000..21c7f1cfd --- /dev/null +++ b/config/moteus/front_left.cfg @@ -0,0 +1,1397 @@ +uuid.uuid.0 229 +uuid.uuid.1 88 +uuid.uuid.2 217 +uuid.uuid.3 47 +uuid.uuid.4 29 +uuid.uuid.5 180 +uuid.uuid.6 75 +uuid.uuid.7 173 +uuid.uuid.8 178 +uuid.uuid.9 53 +uuid.uuid.10 239 +uuid.uuid.11 190 +uuid.uuid.12 69 +uuid.uuid.13 242 +uuid.uuid.14 159 +uuid.uuid.15 48 +clock.hsitrim 64 +aux1.i2c.i2c_hz 400000 +aux1.i2c.i2c_mode 1 +aux1.i2c.pullup 0 +aux1.i2c.devices.0.type 0 +aux1.i2c.devices.0.address 64 +aux1.i2c.devices.0.poll_ms 10 +aux1.i2c.devices.1.type 0 +aux1.i2c.devices.1.address 64 +aux1.i2c.devices.1.poll_ms 10 +aux1.i2c.devices.2.type 0 +aux1.i2c.devices.2.address 64 +aux1.i2c.devices.2.poll_ms 10 +aux1.spi.mode 1 +aux1.spi.rate_hz 12000000 +aux1.spi.filter_us 64 +aux1.spi.bct 0 +aux1.uart.mode 0 +aux1.uart.baud_rate 115200 +aux1.uart.poll_rate_us 100 +aux1.uart.rs422 0 +aux1.uart.cui_amt21_address 84 +aux1.quadrature.enabled 0 +aux1.quadrature.cpr 16384 +aux1.hall.enabled 1 +aux1.hall.polarity 0 +aux1.index.enabled 0 +aux1.sine_cosine.enabled 0 +aux1.sine_cosine.common 1700 +aux1.i2c_startup_delay_ms 30 +aux1.pins.0.mode 6 +aux1.pins.0.pull 1 +aux1.pins.1.mode 6 +aux1.pins.1.pull 1 +aux1.pins.2.mode 6 +aux1.pins.2.pull 1 +aux1.pins.3.mode 0 +aux1.pins.3.pull 0 +aux1.pins.4.mode 0 +aux1.pins.4.pull 0 +aux2.i2c.i2c_hz 400000 +aux2.i2c.i2c_mode 1 +aux2.i2c.pullup 0 +aux2.i2c.devices.0.type 0 +aux2.i2c.devices.0.address 64 +aux2.i2c.devices.0.poll_ms 10 +aux2.i2c.devices.1.type 0 +aux2.i2c.devices.1.address 64 +aux2.i2c.devices.1.poll_ms 10 +aux2.i2c.devices.2.type 0 +aux2.i2c.devices.2.address 64 +aux2.i2c.devices.2.poll_ms 10 +aux2.spi.mode 1 +aux2.spi.rate_hz 12000000 +aux2.spi.filter_us 64 +aux2.spi.bct 0 +aux2.uart.mode 0 +aux2.uart.baud_rate 115200 +aux2.uart.poll_rate_us 100 +aux2.uart.rs422 0 +aux2.uart.cui_amt21_address 84 +aux2.quadrature.enabled 0 +aux2.quadrature.cpr 16384 +aux2.hall.enabled 0 +aux2.hall.polarity 0 +aux2.index.enabled 0 +aux2.sine_cosine.enabled 0 +aux2.sine_cosine.common 1700 +aux2.i2c_startup_delay_ms 30 +aux2.pins.0.mode 0 +aux2.pins.0.pull 0 +aux2.pins.1.mode 0 +aux2.pins.1.pull 0 +aux2.pins.2.mode 0 +aux2.pins.2.pull 0 +aux2.pins.3.mode 0 +aux2.pins.3.pull 0 +aux2.pins.4.mode 0 +aux2.pins.4.pull 0 +motor_position.sources.0.aux_number 1 +motor_position.sources.0.type 4 +motor_position.sources.0.i2c_device 0 +motor_position.sources.0.incremental_index -1 +motor_position.sources.0.cpr 84 +motor_position.sources.0.offset -5.000000 +motor_position.sources.0.sign 1 +motor_position.sources.0.debug_override -1 +motor_position.sources.0.reference 0 +motor_position.sources.0.pll_filter_hz 61.997570 +motor_position.sources.0.compensation_table.0 0.000000 +motor_position.sources.0.compensation_table.1 0.000000 +motor_position.sources.0.compensation_table.2 0.000000 +motor_position.sources.0.compensation_table.3 0.000000 +motor_position.sources.0.compensation_table.4 0.000000 +motor_position.sources.0.compensation_table.5 0.000000 +motor_position.sources.0.compensation_table.6 0.000000 +motor_position.sources.0.compensation_table.7 0.000000 +motor_position.sources.0.compensation_table.8 0.000000 +motor_position.sources.0.compensation_table.9 0.000000 +motor_position.sources.0.compensation_table.10 0.000000 +motor_position.sources.0.compensation_table.11 0.000000 +motor_position.sources.0.compensation_table.12 0.000000 +motor_position.sources.0.compensation_table.13 0.000000 +motor_position.sources.0.compensation_table.14 0.000000 +motor_position.sources.0.compensation_table.15 0.000000 +motor_position.sources.0.compensation_table.16 0.000000 +motor_position.sources.0.compensation_table.17 0.000000 +motor_position.sources.0.compensation_table.18 0.000000 +motor_position.sources.0.compensation_table.19 0.000000 +motor_position.sources.0.compensation_table.20 0.000000 +motor_position.sources.0.compensation_table.21 0.000000 +motor_position.sources.0.compensation_table.22 0.000000 +motor_position.sources.0.compensation_table.23 0.000000 +motor_position.sources.0.compensation_table.24 0.000000 +motor_position.sources.0.compensation_table.25 0.000000 +motor_position.sources.0.compensation_table.26 0.000000 +motor_position.sources.0.compensation_table.27 0.000000 +motor_position.sources.0.compensation_table.28 0.000000 +motor_position.sources.0.compensation_table.29 0.000000 +motor_position.sources.0.compensation_table.30 0.000000 +motor_position.sources.0.compensation_table.31 0.000000 +motor_position.sources.1.aux_number 1 +motor_position.sources.1.type 0 +motor_position.sources.1.i2c_device 0 +motor_position.sources.1.incremental_index -1 +motor_position.sources.1.cpr 16384 +motor_position.sources.1.offset 0.000000 +motor_position.sources.1.sign 1 +motor_position.sources.1.debug_override -1 +motor_position.sources.1.reference 0 +motor_position.sources.1.pll_filter_hz 400.000000 +motor_position.sources.1.compensation_table.0 0.000000 +motor_position.sources.1.compensation_table.1 0.000000 +motor_position.sources.1.compensation_table.2 0.000000 +motor_position.sources.1.compensation_table.3 0.000000 +motor_position.sources.1.compensation_table.4 0.000000 +motor_position.sources.1.compensation_table.5 0.000000 +motor_position.sources.1.compensation_table.6 0.000000 +motor_position.sources.1.compensation_table.7 0.000000 +motor_position.sources.1.compensation_table.8 0.000000 +motor_position.sources.1.compensation_table.9 0.000000 +motor_position.sources.1.compensation_table.10 0.000000 +motor_position.sources.1.compensation_table.11 0.000000 +motor_position.sources.1.compensation_table.12 0.000000 +motor_position.sources.1.compensation_table.13 0.000000 +motor_position.sources.1.compensation_table.14 0.000000 +motor_position.sources.1.compensation_table.15 0.000000 +motor_position.sources.1.compensation_table.16 0.000000 +motor_position.sources.1.compensation_table.17 0.000000 +motor_position.sources.1.compensation_table.18 0.000000 +motor_position.sources.1.compensation_table.19 0.000000 +motor_position.sources.1.compensation_table.20 0.000000 +motor_position.sources.1.compensation_table.21 0.000000 +motor_position.sources.1.compensation_table.22 0.000000 +motor_position.sources.1.compensation_table.23 0.000000 +motor_position.sources.1.compensation_table.24 0.000000 +motor_position.sources.1.compensation_table.25 0.000000 +motor_position.sources.1.compensation_table.26 0.000000 +motor_position.sources.1.compensation_table.27 0.000000 +motor_position.sources.1.compensation_table.28 0.000000 +motor_position.sources.1.compensation_table.29 0.000000 +motor_position.sources.1.compensation_table.30 0.000000 +motor_position.sources.1.compensation_table.31 0.000000 +motor_position.sources.2.aux_number 1 +motor_position.sources.2.type 0 +motor_position.sources.2.i2c_device 0 +motor_position.sources.2.incremental_index -1 +motor_position.sources.2.cpr 16384 +motor_position.sources.2.offset 0.000000 +motor_position.sources.2.sign 1 +motor_position.sources.2.debug_override -1 +motor_position.sources.2.reference 0 +motor_position.sources.2.pll_filter_hz 400.000000 +motor_position.sources.2.compensation_table.0 0.000000 +motor_position.sources.2.compensation_table.1 0.000000 +motor_position.sources.2.compensation_table.2 0.000000 +motor_position.sources.2.compensation_table.3 0.000000 +motor_position.sources.2.compensation_table.4 0.000000 +motor_position.sources.2.compensation_table.5 0.000000 +motor_position.sources.2.compensation_table.6 0.000000 +motor_position.sources.2.compensation_table.7 0.000000 +motor_position.sources.2.compensation_table.8 0.000000 +motor_position.sources.2.compensation_table.9 0.000000 +motor_position.sources.2.compensation_table.10 0.000000 +motor_position.sources.2.compensation_table.11 0.000000 +motor_position.sources.2.compensation_table.12 0.000000 +motor_position.sources.2.compensation_table.13 0.000000 +motor_position.sources.2.compensation_table.14 0.000000 +motor_position.sources.2.compensation_table.15 0.000000 +motor_position.sources.2.compensation_table.16 0.000000 +motor_position.sources.2.compensation_table.17 0.000000 +motor_position.sources.2.compensation_table.18 0.000000 +motor_position.sources.2.compensation_table.19 0.000000 +motor_position.sources.2.compensation_table.20 0.000000 +motor_position.sources.2.compensation_table.21 0.000000 +motor_position.sources.2.compensation_table.22 0.000000 +motor_position.sources.2.compensation_table.23 0.000000 +motor_position.sources.2.compensation_table.24 0.000000 +motor_position.sources.2.compensation_table.25 0.000000 +motor_position.sources.2.compensation_table.26 0.000000 +motor_position.sources.2.compensation_table.27 0.000000 +motor_position.sources.2.compensation_table.28 0.000000 +motor_position.sources.2.compensation_table.29 0.000000 +motor_position.sources.2.compensation_table.30 0.000000 +motor_position.sources.2.compensation_table.31 0.000000 +motor_position.commutation_source 0 +motor_position.output.source 0 +motor_position.output.offset 0.000000 +motor_position.output.sign -1 +motor_position.output.reference_source -1 +motor_position.rotor_to_output_ratio 1.000000 +motor.poles 28 +motor.phase_invert 0 +motor.resistance_ohm 0.235030 +motor.v_per_hz 0.437548 +motor.offset.0 0.000000 +motor.offset.1 0.000000 +motor.offset.2 0.000000 +motor.offset.3 0.000000 +motor.offset.4 0.000000 +motor.offset.5 0.000000 +motor.offset.6 0.000000 +motor.offset.7 0.000000 +motor.offset.8 0.000000 +motor.offset.9 0.000000 +motor.offset.10 0.000000 +motor.offset.11 0.000000 +motor.offset.12 0.000000 +motor.offset.13 0.000000 +motor.offset.14 0.000000 +motor.offset.15 0.000000 +motor.offset.16 0.000000 +motor.offset.17 0.000000 +motor.offset.18 0.000000 +motor.offset.19 0.000000 +motor.offset.20 0.000000 +motor.offset.21 0.000000 +motor.offset.22 0.000000 +motor.offset.23 0.000000 +motor.offset.24 0.000000 +motor.offset.25 0.000000 +motor.offset.26 0.000000 +motor.offset.27 0.000000 +motor.offset.28 0.000000 +motor.offset.29 0.000000 +motor.offset.30 0.000000 +motor.offset.31 0.000000 +motor.offset.32 0.000000 +motor.offset.33 0.000000 +motor.offset.34 0.000000 +motor.offset.35 0.000000 +motor.offset.36 0.000000 +motor.offset.37 0.000000 +motor.offset.38 0.000000 +motor.offset.39 0.000000 +motor.offset.40 0.000000 +motor.offset.41 0.000000 +motor.offset.42 0.000000 +motor.offset.43 0.000000 +motor.offset.44 0.000000 +motor.offset.45 0.000000 +motor.offset.46 0.000000 +motor.offset.47 0.000000 +motor.offset.48 0.000000 +motor.offset.49 0.000000 +motor.offset.50 0.000000 +motor.offset.51 0.000000 +motor.offset.52 0.000000 +motor.offset.53 0.000000 +motor.offset.54 0.000000 +motor.offset.55 0.000000 +motor.offset.56 0.000000 +motor.offset.57 0.000000 +motor.offset.58 0.000000 +motor.offset.59 0.000000 +motor.offset.60 0.000000 +motor.offset.61 0.000000 +motor.offset.62 0.000000 +motor.offset.63 0.000000 +motor.rotation_current_cutoff_A 10000.000000 +motor.rotation_current_scale 0.050000 +motor.rotation_torque_scale 14.700000 +motor.cogging_dq_scale 0.000000 +motor.cogging_dq_comp.0 0 +motor.cogging_dq_comp.1 0 +motor.cogging_dq_comp.2 0 +motor.cogging_dq_comp.3 0 +motor.cogging_dq_comp.4 0 +motor.cogging_dq_comp.5 0 +motor.cogging_dq_comp.6 0 +motor.cogging_dq_comp.7 0 +motor.cogging_dq_comp.8 0 +motor.cogging_dq_comp.9 0 +motor.cogging_dq_comp.10 0 +motor.cogging_dq_comp.11 0 +motor.cogging_dq_comp.12 0 +motor.cogging_dq_comp.13 0 +motor.cogging_dq_comp.14 0 +motor.cogging_dq_comp.15 0 +motor.cogging_dq_comp.16 0 +motor.cogging_dq_comp.17 0 +motor.cogging_dq_comp.18 0 +motor.cogging_dq_comp.19 0 +motor.cogging_dq_comp.20 0 +motor.cogging_dq_comp.21 0 +motor.cogging_dq_comp.22 0 +motor.cogging_dq_comp.23 0 +motor.cogging_dq_comp.24 0 +motor.cogging_dq_comp.25 0 +motor.cogging_dq_comp.26 0 +motor.cogging_dq_comp.27 0 +motor.cogging_dq_comp.28 0 +motor.cogging_dq_comp.29 0 +motor.cogging_dq_comp.30 0 +motor.cogging_dq_comp.31 0 +motor.cogging_dq_comp.32 0 +motor.cogging_dq_comp.33 0 +motor.cogging_dq_comp.34 0 +motor.cogging_dq_comp.35 0 +motor.cogging_dq_comp.36 0 +motor.cogging_dq_comp.37 0 +motor.cogging_dq_comp.38 0 +motor.cogging_dq_comp.39 0 +motor.cogging_dq_comp.40 0 +motor.cogging_dq_comp.41 0 +motor.cogging_dq_comp.42 0 +motor.cogging_dq_comp.43 0 +motor.cogging_dq_comp.44 0 +motor.cogging_dq_comp.45 0 +motor.cogging_dq_comp.46 0 +motor.cogging_dq_comp.47 0 +motor.cogging_dq_comp.48 0 +motor.cogging_dq_comp.49 0 +motor.cogging_dq_comp.50 0 +motor.cogging_dq_comp.51 0 +motor.cogging_dq_comp.52 0 +motor.cogging_dq_comp.53 0 +motor.cogging_dq_comp.54 0 +motor.cogging_dq_comp.55 0 +motor.cogging_dq_comp.56 0 +motor.cogging_dq_comp.57 0 +motor.cogging_dq_comp.58 0 +motor.cogging_dq_comp.59 0 +motor.cogging_dq_comp.60 0 +motor.cogging_dq_comp.61 0 +motor.cogging_dq_comp.62 0 +motor.cogging_dq_comp.63 0 +motor.cogging_dq_comp.64 0 +motor.cogging_dq_comp.65 0 +motor.cogging_dq_comp.66 0 +motor.cogging_dq_comp.67 0 +motor.cogging_dq_comp.68 0 +motor.cogging_dq_comp.69 0 +motor.cogging_dq_comp.70 0 +motor.cogging_dq_comp.71 0 +motor.cogging_dq_comp.72 0 +motor.cogging_dq_comp.73 0 +motor.cogging_dq_comp.74 0 +motor.cogging_dq_comp.75 0 +motor.cogging_dq_comp.76 0 +motor.cogging_dq_comp.77 0 +motor.cogging_dq_comp.78 0 +motor.cogging_dq_comp.79 0 +motor.cogging_dq_comp.80 0 +motor.cogging_dq_comp.81 0 +motor.cogging_dq_comp.82 0 +motor.cogging_dq_comp.83 0 +motor.cogging_dq_comp.84 0 +motor.cogging_dq_comp.85 0 +motor.cogging_dq_comp.86 0 +motor.cogging_dq_comp.87 0 +motor.cogging_dq_comp.88 0 +motor.cogging_dq_comp.89 0 +motor.cogging_dq_comp.90 0 +motor.cogging_dq_comp.91 0 +motor.cogging_dq_comp.92 0 +motor.cogging_dq_comp.93 0 +motor.cogging_dq_comp.94 0 +motor.cogging_dq_comp.95 0 +motor.cogging_dq_comp.96 0 +motor.cogging_dq_comp.97 0 +motor.cogging_dq_comp.98 0 +motor.cogging_dq_comp.99 0 +motor.cogging_dq_comp.100 0 +motor.cogging_dq_comp.101 0 +motor.cogging_dq_comp.102 0 +motor.cogging_dq_comp.103 0 +motor.cogging_dq_comp.104 0 +motor.cogging_dq_comp.105 0 +motor.cogging_dq_comp.106 0 +motor.cogging_dq_comp.107 0 +motor.cogging_dq_comp.108 0 +motor.cogging_dq_comp.109 0 +motor.cogging_dq_comp.110 0 +motor.cogging_dq_comp.111 0 +motor.cogging_dq_comp.112 0 +motor.cogging_dq_comp.113 0 +motor.cogging_dq_comp.114 0 +motor.cogging_dq_comp.115 0 +motor.cogging_dq_comp.116 0 +motor.cogging_dq_comp.117 0 +motor.cogging_dq_comp.118 0 +motor.cogging_dq_comp.119 0 +motor.cogging_dq_comp.120 0 +motor.cogging_dq_comp.121 0 +motor.cogging_dq_comp.122 0 +motor.cogging_dq_comp.123 0 +motor.cogging_dq_comp.124 0 +motor.cogging_dq_comp.125 0 +motor.cogging_dq_comp.126 0 +motor.cogging_dq_comp.127 0 +motor.cogging_dq_comp.128 0 +motor.cogging_dq_comp.129 0 +motor.cogging_dq_comp.130 0 +motor.cogging_dq_comp.131 0 +motor.cogging_dq_comp.132 0 +motor.cogging_dq_comp.133 0 +motor.cogging_dq_comp.134 0 +motor.cogging_dq_comp.135 0 +motor.cogging_dq_comp.136 0 +motor.cogging_dq_comp.137 0 +motor.cogging_dq_comp.138 0 +motor.cogging_dq_comp.139 0 +motor.cogging_dq_comp.140 0 +motor.cogging_dq_comp.141 0 +motor.cogging_dq_comp.142 0 +motor.cogging_dq_comp.143 0 +motor.cogging_dq_comp.144 0 +motor.cogging_dq_comp.145 0 +motor.cogging_dq_comp.146 0 +motor.cogging_dq_comp.147 0 +motor.cogging_dq_comp.148 0 +motor.cogging_dq_comp.149 0 +motor.cogging_dq_comp.150 0 +motor.cogging_dq_comp.151 0 +motor.cogging_dq_comp.152 0 +motor.cogging_dq_comp.153 0 +motor.cogging_dq_comp.154 0 +motor.cogging_dq_comp.155 0 +motor.cogging_dq_comp.156 0 +motor.cogging_dq_comp.157 0 +motor.cogging_dq_comp.158 0 +motor.cogging_dq_comp.159 0 +motor.cogging_dq_comp.160 0 +motor.cogging_dq_comp.161 0 +motor.cogging_dq_comp.162 0 +motor.cogging_dq_comp.163 0 +motor.cogging_dq_comp.164 0 +motor.cogging_dq_comp.165 0 +motor.cogging_dq_comp.166 0 +motor.cogging_dq_comp.167 0 +motor.cogging_dq_comp.168 0 +motor.cogging_dq_comp.169 0 +motor.cogging_dq_comp.170 0 +motor.cogging_dq_comp.171 0 +motor.cogging_dq_comp.172 0 +motor.cogging_dq_comp.173 0 +motor.cogging_dq_comp.174 0 +motor.cogging_dq_comp.175 0 +motor.cogging_dq_comp.176 0 +motor.cogging_dq_comp.177 0 +motor.cogging_dq_comp.178 0 +motor.cogging_dq_comp.179 0 +motor.cogging_dq_comp.180 0 +motor.cogging_dq_comp.181 0 +motor.cogging_dq_comp.182 0 +motor.cogging_dq_comp.183 0 +motor.cogging_dq_comp.184 0 +motor.cogging_dq_comp.185 0 +motor.cogging_dq_comp.186 0 +motor.cogging_dq_comp.187 0 +motor.cogging_dq_comp.188 0 +motor.cogging_dq_comp.189 0 +motor.cogging_dq_comp.190 0 +motor.cogging_dq_comp.191 0 +motor.cogging_dq_comp.192 0 +motor.cogging_dq_comp.193 0 +motor.cogging_dq_comp.194 0 +motor.cogging_dq_comp.195 0 +motor.cogging_dq_comp.196 0 +motor.cogging_dq_comp.197 0 +motor.cogging_dq_comp.198 0 +motor.cogging_dq_comp.199 0 +motor.cogging_dq_comp.200 0 +motor.cogging_dq_comp.201 0 +motor.cogging_dq_comp.202 0 +motor.cogging_dq_comp.203 0 +motor.cogging_dq_comp.204 0 +motor.cogging_dq_comp.205 0 +motor.cogging_dq_comp.206 0 +motor.cogging_dq_comp.207 0 +motor.cogging_dq_comp.208 0 +motor.cogging_dq_comp.209 0 +motor.cogging_dq_comp.210 0 +motor.cogging_dq_comp.211 0 +motor.cogging_dq_comp.212 0 +motor.cogging_dq_comp.213 0 +motor.cogging_dq_comp.214 0 +motor.cogging_dq_comp.215 0 +motor.cogging_dq_comp.216 0 +motor.cogging_dq_comp.217 0 +motor.cogging_dq_comp.218 0 +motor.cogging_dq_comp.219 0 +motor.cogging_dq_comp.220 0 +motor.cogging_dq_comp.221 0 +motor.cogging_dq_comp.222 0 +motor.cogging_dq_comp.223 0 +motor.cogging_dq_comp.224 0 +motor.cogging_dq_comp.225 0 +motor.cogging_dq_comp.226 0 +motor.cogging_dq_comp.227 0 +motor.cogging_dq_comp.228 0 +motor.cogging_dq_comp.229 0 +motor.cogging_dq_comp.230 0 +motor.cogging_dq_comp.231 0 +motor.cogging_dq_comp.232 0 +motor.cogging_dq_comp.233 0 +motor.cogging_dq_comp.234 0 +motor.cogging_dq_comp.235 0 +motor.cogging_dq_comp.236 0 +motor.cogging_dq_comp.237 0 +motor.cogging_dq_comp.238 0 +motor.cogging_dq_comp.239 0 +motor.cogging_dq_comp.240 0 +motor.cogging_dq_comp.241 0 +motor.cogging_dq_comp.242 0 +motor.cogging_dq_comp.243 0 +motor.cogging_dq_comp.244 0 +motor.cogging_dq_comp.245 0 +motor.cogging_dq_comp.246 0 +motor.cogging_dq_comp.247 0 +motor.cogging_dq_comp.248 0 +motor.cogging_dq_comp.249 0 +motor.cogging_dq_comp.250 0 +motor.cogging_dq_comp.251 0 +motor.cogging_dq_comp.252 0 +motor.cogging_dq_comp.253 0 +motor.cogging_dq_comp.254 0 +motor.cogging_dq_comp.255 0 +motor.cogging_dq_comp.256 0 +motor.cogging_dq_comp.257 0 +motor.cogging_dq_comp.258 0 +motor.cogging_dq_comp.259 0 +motor.cogging_dq_comp.260 0 +motor.cogging_dq_comp.261 0 +motor.cogging_dq_comp.262 0 +motor.cogging_dq_comp.263 0 +motor.cogging_dq_comp.264 0 +motor.cogging_dq_comp.265 0 +motor.cogging_dq_comp.266 0 +motor.cogging_dq_comp.267 0 +motor.cogging_dq_comp.268 0 +motor.cogging_dq_comp.269 0 +motor.cogging_dq_comp.270 0 +motor.cogging_dq_comp.271 0 +motor.cogging_dq_comp.272 0 +motor.cogging_dq_comp.273 0 +motor.cogging_dq_comp.274 0 +motor.cogging_dq_comp.275 0 +motor.cogging_dq_comp.276 0 +motor.cogging_dq_comp.277 0 +motor.cogging_dq_comp.278 0 +motor.cogging_dq_comp.279 0 +motor.cogging_dq_comp.280 0 +motor.cogging_dq_comp.281 0 +motor.cogging_dq_comp.282 0 +motor.cogging_dq_comp.283 0 +motor.cogging_dq_comp.284 0 +motor.cogging_dq_comp.285 0 +motor.cogging_dq_comp.286 0 +motor.cogging_dq_comp.287 0 +motor.cogging_dq_comp.288 0 +motor.cogging_dq_comp.289 0 +motor.cogging_dq_comp.290 0 +motor.cogging_dq_comp.291 0 +motor.cogging_dq_comp.292 0 +motor.cogging_dq_comp.293 0 +motor.cogging_dq_comp.294 0 +motor.cogging_dq_comp.295 0 +motor.cogging_dq_comp.296 0 +motor.cogging_dq_comp.297 0 +motor.cogging_dq_comp.298 0 +motor.cogging_dq_comp.299 0 +motor.cogging_dq_comp.300 0 +motor.cogging_dq_comp.301 0 +motor.cogging_dq_comp.302 0 +motor.cogging_dq_comp.303 0 +motor.cogging_dq_comp.304 0 +motor.cogging_dq_comp.305 0 +motor.cogging_dq_comp.306 0 +motor.cogging_dq_comp.307 0 +motor.cogging_dq_comp.308 0 +motor.cogging_dq_comp.309 0 +motor.cogging_dq_comp.310 0 +motor.cogging_dq_comp.311 0 +motor.cogging_dq_comp.312 0 +motor.cogging_dq_comp.313 0 +motor.cogging_dq_comp.314 0 +motor.cogging_dq_comp.315 0 +motor.cogging_dq_comp.316 0 +motor.cogging_dq_comp.317 0 +motor.cogging_dq_comp.318 0 +motor.cogging_dq_comp.319 0 +motor.cogging_dq_comp.320 0 +motor.cogging_dq_comp.321 0 +motor.cogging_dq_comp.322 0 +motor.cogging_dq_comp.323 0 +motor.cogging_dq_comp.324 0 +motor.cogging_dq_comp.325 0 +motor.cogging_dq_comp.326 0 +motor.cogging_dq_comp.327 0 +motor.cogging_dq_comp.328 0 +motor.cogging_dq_comp.329 0 +motor.cogging_dq_comp.330 0 +motor.cogging_dq_comp.331 0 +motor.cogging_dq_comp.332 0 +motor.cogging_dq_comp.333 0 +motor.cogging_dq_comp.334 0 +motor.cogging_dq_comp.335 0 +motor.cogging_dq_comp.336 0 +motor.cogging_dq_comp.337 0 +motor.cogging_dq_comp.338 0 +motor.cogging_dq_comp.339 0 +motor.cogging_dq_comp.340 0 +motor.cogging_dq_comp.341 0 +motor.cogging_dq_comp.342 0 +motor.cogging_dq_comp.343 0 +motor.cogging_dq_comp.344 0 +motor.cogging_dq_comp.345 0 +motor.cogging_dq_comp.346 0 +motor.cogging_dq_comp.347 0 +motor.cogging_dq_comp.348 0 +motor.cogging_dq_comp.349 0 +motor.cogging_dq_comp.350 0 +motor.cogging_dq_comp.351 0 +motor.cogging_dq_comp.352 0 +motor.cogging_dq_comp.353 0 +motor.cogging_dq_comp.354 0 +motor.cogging_dq_comp.355 0 +motor.cogging_dq_comp.356 0 +motor.cogging_dq_comp.357 0 +motor.cogging_dq_comp.358 0 +motor.cogging_dq_comp.359 0 +motor.cogging_dq_comp.360 0 +motor.cogging_dq_comp.361 0 +motor.cogging_dq_comp.362 0 +motor.cogging_dq_comp.363 0 +motor.cogging_dq_comp.364 0 +motor.cogging_dq_comp.365 0 +motor.cogging_dq_comp.366 0 +motor.cogging_dq_comp.367 0 +motor.cogging_dq_comp.368 0 +motor.cogging_dq_comp.369 0 +motor.cogging_dq_comp.370 0 +motor.cogging_dq_comp.371 0 +motor.cogging_dq_comp.372 0 +motor.cogging_dq_comp.373 0 +motor.cogging_dq_comp.374 0 +motor.cogging_dq_comp.375 0 +motor.cogging_dq_comp.376 0 +motor.cogging_dq_comp.377 0 +motor.cogging_dq_comp.378 0 +motor.cogging_dq_comp.379 0 +motor.cogging_dq_comp.380 0 +motor.cogging_dq_comp.381 0 +motor.cogging_dq_comp.382 0 +motor.cogging_dq_comp.383 0 +motor.cogging_dq_comp.384 0 +motor.cogging_dq_comp.385 0 +motor.cogging_dq_comp.386 0 +motor.cogging_dq_comp.387 0 +motor.cogging_dq_comp.388 0 +motor.cogging_dq_comp.389 0 +motor.cogging_dq_comp.390 0 +motor.cogging_dq_comp.391 0 +motor.cogging_dq_comp.392 0 +motor.cogging_dq_comp.393 0 +motor.cogging_dq_comp.394 0 +motor.cogging_dq_comp.395 0 +motor.cogging_dq_comp.396 0 +motor.cogging_dq_comp.397 0 +motor.cogging_dq_comp.398 0 +motor.cogging_dq_comp.399 0 +motor.cogging_dq_comp.400 0 +motor.cogging_dq_comp.401 0 +motor.cogging_dq_comp.402 0 +motor.cogging_dq_comp.403 0 +motor.cogging_dq_comp.404 0 +motor.cogging_dq_comp.405 0 +motor.cogging_dq_comp.406 0 +motor.cogging_dq_comp.407 0 +motor.cogging_dq_comp.408 0 +motor.cogging_dq_comp.409 0 +motor.cogging_dq_comp.410 0 +motor.cogging_dq_comp.411 0 +motor.cogging_dq_comp.412 0 +motor.cogging_dq_comp.413 0 +motor.cogging_dq_comp.414 0 +motor.cogging_dq_comp.415 0 +motor.cogging_dq_comp.416 0 +motor.cogging_dq_comp.417 0 +motor.cogging_dq_comp.418 0 +motor.cogging_dq_comp.419 0 +motor.cogging_dq_comp.420 0 +motor.cogging_dq_comp.421 0 +motor.cogging_dq_comp.422 0 +motor.cogging_dq_comp.423 0 +motor.cogging_dq_comp.424 0 +motor.cogging_dq_comp.425 0 +motor.cogging_dq_comp.426 0 +motor.cogging_dq_comp.427 0 +motor.cogging_dq_comp.428 0 +motor.cogging_dq_comp.429 0 +motor.cogging_dq_comp.430 0 +motor.cogging_dq_comp.431 0 +motor.cogging_dq_comp.432 0 +motor.cogging_dq_comp.433 0 +motor.cogging_dq_comp.434 0 +motor.cogging_dq_comp.435 0 +motor.cogging_dq_comp.436 0 +motor.cogging_dq_comp.437 0 +motor.cogging_dq_comp.438 0 +motor.cogging_dq_comp.439 0 +motor.cogging_dq_comp.440 0 +motor.cogging_dq_comp.441 0 +motor.cogging_dq_comp.442 0 +motor.cogging_dq_comp.443 0 +motor.cogging_dq_comp.444 0 +motor.cogging_dq_comp.445 0 +motor.cogging_dq_comp.446 0 +motor.cogging_dq_comp.447 0 +motor.cogging_dq_comp.448 0 +motor.cogging_dq_comp.449 0 +motor.cogging_dq_comp.450 0 +motor.cogging_dq_comp.451 0 +motor.cogging_dq_comp.452 0 +motor.cogging_dq_comp.453 0 +motor.cogging_dq_comp.454 0 +motor.cogging_dq_comp.455 0 +motor.cogging_dq_comp.456 0 +motor.cogging_dq_comp.457 0 +motor.cogging_dq_comp.458 0 +motor.cogging_dq_comp.459 0 +motor.cogging_dq_comp.460 0 +motor.cogging_dq_comp.461 0 +motor.cogging_dq_comp.462 0 +motor.cogging_dq_comp.463 0 +motor.cogging_dq_comp.464 0 +motor.cogging_dq_comp.465 0 +motor.cogging_dq_comp.466 0 +motor.cogging_dq_comp.467 0 +motor.cogging_dq_comp.468 0 +motor.cogging_dq_comp.469 0 +motor.cogging_dq_comp.470 0 +motor.cogging_dq_comp.471 0 +motor.cogging_dq_comp.472 0 +motor.cogging_dq_comp.473 0 +motor.cogging_dq_comp.474 0 +motor.cogging_dq_comp.475 0 +motor.cogging_dq_comp.476 0 +motor.cogging_dq_comp.477 0 +motor.cogging_dq_comp.478 0 +motor.cogging_dq_comp.479 0 +motor.cogging_dq_comp.480 0 +motor.cogging_dq_comp.481 0 +motor.cogging_dq_comp.482 0 +motor.cogging_dq_comp.483 0 +motor.cogging_dq_comp.484 0 +motor.cogging_dq_comp.485 0 +motor.cogging_dq_comp.486 0 +motor.cogging_dq_comp.487 0 +motor.cogging_dq_comp.488 0 +motor.cogging_dq_comp.489 0 +motor.cogging_dq_comp.490 0 +motor.cogging_dq_comp.491 0 +motor.cogging_dq_comp.492 0 +motor.cogging_dq_comp.493 0 +motor.cogging_dq_comp.494 0 +motor.cogging_dq_comp.495 0 +motor.cogging_dq_comp.496 0 +motor.cogging_dq_comp.497 0 +motor.cogging_dq_comp.498 0 +motor.cogging_dq_comp.499 0 +motor.cogging_dq_comp.500 0 +motor.cogging_dq_comp.501 0 +motor.cogging_dq_comp.502 0 +motor.cogging_dq_comp.503 0 +motor.cogging_dq_comp.504 0 +motor.cogging_dq_comp.505 0 +motor.cogging_dq_comp.506 0 +motor.cogging_dq_comp.507 0 +motor.cogging_dq_comp.508 0 +motor.cogging_dq_comp.509 0 +motor.cogging_dq_comp.510 0 +motor.cogging_dq_comp.511 0 +motor.cogging_dq_comp.512 0 +motor.cogging_dq_comp.513 0 +motor.cogging_dq_comp.514 0 +motor.cogging_dq_comp.515 0 +motor.cogging_dq_comp.516 0 +motor.cogging_dq_comp.517 0 +motor.cogging_dq_comp.518 0 +motor.cogging_dq_comp.519 0 +motor.cogging_dq_comp.520 0 +motor.cogging_dq_comp.521 0 +motor.cogging_dq_comp.522 0 +motor.cogging_dq_comp.523 0 +motor.cogging_dq_comp.524 0 +motor.cogging_dq_comp.525 0 +motor.cogging_dq_comp.526 0 +motor.cogging_dq_comp.527 0 +motor.cogging_dq_comp.528 0 +motor.cogging_dq_comp.529 0 +motor.cogging_dq_comp.530 0 +motor.cogging_dq_comp.531 0 +motor.cogging_dq_comp.532 0 +motor.cogging_dq_comp.533 0 +motor.cogging_dq_comp.534 0 +motor.cogging_dq_comp.535 0 +motor.cogging_dq_comp.536 0 +motor.cogging_dq_comp.537 0 +motor.cogging_dq_comp.538 0 +motor.cogging_dq_comp.539 0 +motor.cogging_dq_comp.540 0 +motor.cogging_dq_comp.541 0 +motor.cogging_dq_comp.542 0 +motor.cogging_dq_comp.543 0 +motor.cogging_dq_comp.544 0 +motor.cogging_dq_comp.545 0 +motor.cogging_dq_comp.546 0 +motor.cogging_dq_comp.547 0 +motor.cogging_dq_comp.548 0 +motor.cogging_dq_comp.549 0 +motor.cogging_dq_comp.550 0 +motor.cogging_dq_comp.551 0 +motor.cogging_dq_comp.552 0 +motor.cogging_dq_comp.553 0 +motor.cogging_dq_comp.554 0 +motor.cogging_dq_comp.555 0 +motor.cogging_dq_comp.556 0 +motor.cogging_dq_comp.557 0 +motor.cogging_dq_comp.558 0 +motor.cogging_dq_comp.559 0 +motor.cogging_dq_comp.560 0 +motor.cogging_dq_comp.561 0 +motor.cogging_dq_comp.562 0 +motor.cogging_dq_comp.563 0 +motor.cogging_dq_comp.564 0 +motor.cogging_dq_comp.565 0 +motor.cogging_dq_comp.566 0 +motor.cogging_dq_comp.567 0 +motor.cogging_dq_comp.568 0 +motor.cogging_dq_comp.569 0 +motor.cogging_dq_comp.570 0 +motor.cogging_dq_comp.571 0 +motor.cogging_dq_comp.572 0 +motor.cogging_dq_comp.573 0 +motor.cogging_dq_comp.574 0 +motor.cogging_dq_comp.575 0 +motor.cogging_dq_comp.576 0 +motor.cogging_dq_comp.577 0 +motor.cogging_dq_comp.578 0 +motor.cogging_dq_comp.579 0 +motor.cogging_dq_comp.580 0 +motor.cogging_dq_comp.581 0 +motor.cogging_dq_comp.582 0 +motor.cogging_dq_comp.583 0 +motor.cogging_dq_comp.584 0 +motor.cogging_dq_comp.585 0 +motor.cogging_dq_comp.586 0 +motor.cogging_dq_comp.587 0 +motor.cogging_dq_comp.588 0 +motor.cogging_dq_comp.589 0 +motor.cogging_dq_comp.590 0 +motor.cogging_dq_comp.591 0 +motor.cogging_dq_comp.592 0 +motor.cogging_dq_comp.593 0 +motor.cogging_dq_comp.594 0 +motor.cogging_dq_comp.595 0 +motor.cogging_dq_comp.596 0 +motor.cogging_dq_comp.597 0 +motor.cogging_dq_comp.598 0 +motor.cogging_dq_comp.599 0 +motor.cogging_dq_comp.600 0 +motor.cogging_dq_comp.601 0 +motor.cogging_dq_comp.602 0 +motor.cogging_dq_comp.603 0 +motor.cogging_dq_comp.604 0 +motor.cogging_dq_comp.605 0 +motor.cogging_dq_comp.606 0 +motor.cogging_dq_comp.607 0 +motor.cogging_dq_comp.608 0 +motor.cogging_dq_comp.609 0 +motor.cogging_dq_comp.610 0 +motor.cogging_dq_comp.611 0 +motor.cogging_dq_comp.612 0 +motor.cogging_dq_comp.613 0 +motor.cogging_dq_comp.614 0 +motor.cogging_dq_comp.615 0 +motor.cogging_dq_comp.616 0 +motor.cogging_dq_comp.617 0 +motor.cogging_dq_comp.618 0 +motor.cogging_dq_comp.619 0 +motor.cogging_dq_comp.620 0 +motor.cogging_dq_comp.621 0 +motor.cogging_dq_comp.622 0 +motor.cogging_dq_comp.623 0 +motor.cogging_dq_comp.624 0 +motor.cogging_dq_comp.625 0 +motor.cogging_dq_comp.626 0 +motor.cogging_dq_comp.627 0 +motor.cogging_dq_comp.628 0 +motor.cogging_dq_comp.629 0 +motor.cogging_dq_comp.630 0 +motor.cogging_dq_comp.631 0 +motor.cogging_dq_comp.632 0 +motor.cogging_dq_comp.633 0 +motor.cogging_dq_comp.634 0 +motor.cogging_dq_comp.635 0 +motor.cogging_dq_comp.636 0 +motor.cogging_dq_comp.637 0 +motor.cogging_dq_comp.638 0 +motor.cogging_dq_comp.639 0 +motor.cogging_dq_comp.640 0 +motor.cogging_dq_comp.641 0 +motor.cogging_dq_comp.642 0 +motor.cogging_dq_comp.643 0 +motor.cogging_dq_comp.644 0 +motor.cogging_dq_comp.645 0 +motor.cogging_dq_comp.646 0 +motor.cogging_dq_comp.647 0 +motor.cogging_dq_comp.648 0 +motor.cogging_dq_comp.649 0 +motor.cogging_dq_comp.650 0 +motor.cogging_dq_comp.651 0 +motor.cogging_dq_comp.652 0 +motor.cogging_dq_comp.653 0 +motor.cogging_dq_comp.654 0 +motor.cogging_dq_comp.655 0 +motor.cogging_dq_comp.656 0 +motor.cogging_dq_comp.657 0 +motor.cogging_dq_comp.658 0 +motor.cogging_dq_comp.659 0 +motor.cogging_dq_comp.660 0 +motor.cogging_dq_comp.661 0 +motor.cogging_dq_comp.662 0 +motor.cogging_dq_comp.663 0 +motor.cogging_dq_comp.664 0 +motor.cogging_dq_comp.665 0 +motor.cogging_dq_comp.666 0 +motor.cogging_dq_comp.667 0 +motor.cogging_dq_comp.668 0 +motor.cogging_dq_comp.669 0 +motor.cogging_dq_comp.670 0 +motor.cogging_dq_comp.671 0 +motor.cogging_dq_comp.672 0 +motor.cogging_dq_comp.673 0 +motor.cogging_dq_comp.674 0 +motor.cogging_dq_comp.675 0 +motor.cogging_dq_comp.676 0 +motor.cogging_dq_comp.677 0 +motor.cogging_dq_comp.678 0 +motor.cogging_dq_comp.679 0 +motor.cogging_dq_comp.680 0 +motor.cogging_dq_comp.681 0 +motor.cogging_dq_comp.682 0 +motor.cogging_dq_comp.683 0 +motor.cogging_dq_comp.684 0 +motor.cogging_dq_comp.685 0 +motor.cogging_dq_comp.686 0 +motor.cogging_dq_comp.687 0 +motor.cogging_dq_comp.688 0 +motor.cogging_dq_comp.689 0 +motor.cogging_dq_comp.690 0 +motor.cogging_dq_comp.691 0 +motor.cogging_dq_comp.692 0 +motor.cogging_dq_comp.693 0 +motor.cogging_dq_comp.694 0 +motor.cogging_dq_comp.695 0 +motor.cogging_dq_comp.696 0 +motor.cogging_dq_comp.697 0 +motor.cogging_dq_comp.698 0 +motor.cogging_dq_comp.699 0 +motor.cogging_dq_comp.700 0 +motor.cogging_dq_comp.701 0 +motor.cogging_dq_comp.702 0 +motor.cogging_dq_comp.703 0 +motor.cogging_dq_comp.704 0 +motor.cogging_dq_comp.705 0 +motor.cogging_dq_comp.706 0 +motor.cogging_dq_comp.707 0 +motor.cogging_dq_comp.708 0 +motor.cogging_dq_comp.709 0 +motor.cogging_dq_comp.710 0 +motor.cogging_dq_comp.711 0 +motor.cogging_dq_comp.712 0 +motor.cogging_dq_comp.713 0 +motor.cogging_dq_comp.714 0 +motor.cogging_dq_comp.715 0 +motor.cogging_dq_comp.716 0 +motor.cogging_dq_comp.717 0 +motor.cogging_dq_comp.718 0 +motor.cogging_dq_comp.719 0 +motor.cogging_dq_comp.720 0 +motor.cogging_dq_comp.721 0 +motor.cogging_dq_comp.722 0 +motor.cogging_dq_comp.723 0 +motor.cogging_dq_comp.724 0 +motor.cogging_dq_comp.725 0 +motor.cogging_dq_comp.726 0 +motor.cogging_dq_comp.727 0 +motor.cogging_dq_comp.728 0 +motor.cogging_dq_comp.729 0 +motor.cogging_dq_comp.730 0 +motor.cogging_dq_comp.731 0 +motor.cogging_dq_comp.732 0 +motor.cogging_dq_comp.733 0 +motor.cogging_dq_comp.734 0 +motor.cogging_dq_comp.735 0 +motor.cogging_dq_comp.736 0 +motor.cogging_dq_comp.737 0 +motor.cogging_dq_comp.738 0 +motor.cogging_dq_comp.739 0 +motor.cogging_dq_comp.740 0 +motor.cogging_dq_comp.741 0 +motor.cogging_dq_comp.742 0 +motor.cogging_dq_comp.743 0 +motor.cogging_dq_comp.744 0 +motor.cogging_dq_comp.745 0 +motor.cogging_dq_comp.746 0 +motor.cogging_dq_comp.747 0 +motor.cogging_dq_comp.748 0 +motor.cogging_dq_comp.749 0 +motor.cogging_dq_comp.750 0 +motor.cogging_dq_comp.751 0 +motor.cogging_dq_comp.752 0 +motor.cogging_dq_comp.753 0 +motor.cogging_dq_comp.754 0 +motor.cogging_dq_comp.755 0 +motor.cogging_dq_comp.756 0 +motor.cogging_dq_comp.757 0 +motor.cogging_dq_comp.758 0 +motor.cogging_dq_comp.759 0 +motor.cogging_dq_comp.760 0 +motor.cogging_dq_comp.761 0 +motor.cogging_dq_comp.762 0 +motor.cogging_dq_comp.763 0 +motor.cogging_dq_comp.764 0 +motor.cogging_dq_comp.765 0 +motor.cogging_dq_comp.766 0 +motor.cogging_dq_comp.767 0 +motor.cogging_dq_comp.768 0 +motor.cogging_dq_comp.769 0 +motor.cogging_dq_comp.770 0 +motor.cogging_dq_comp.771 0 +motor.cogging_dq_comp.772 0 +motor.cogging_dq_comp.773 0 +motor.cogging_dq_comp.774 0 +motor.cogging_dq_comp.775 0 +motor.cogging_dq_comp.776 0 +motor.cogging_dq_comp.777 0 +motor.cogging_dq_comp.778 0 +motor.cogging_dq_comp.779 0 +motor.cogging_dq_comp.780 0 +motor.cogging_dq_comp.781 0 +motor.cogging_dq_comp.782 0 +motor.cogging_dq_comp.783 0 +motor.cogging_dq_comp.784 0 +motor.cogging_dq_comp.785 0 +motor.cogging_dq_comp.786 0 +motor.cogging_dq_comp.787 0 +motor.cogging_dq_comp.788 0 +motor.cogging_dq_comp.789 0 +motor.cogging_dq_comp.790 0 +motor.cogging_dq_comp.791 0 +motor.cogging_dq_comp.792 0 +motor.cogging_dq_comp.793 0 +motor.cogging_dq_comp.794 0 +motor.cogging_dq_comp.795 0 +motor.cogging_dq_comp.796 0 +motor.cogging_dq_comp.797 0 +motor.cogging_dq_comp.798 0 +motor.cogging_dq_comp.799 0 +motor.cogging_dq_comp.800 0 +motor.cogging_dq_comp.801 0 +motor.cogging_dq_comp.802 0 +motor.cogging_dq_comp.803 0 +motor.cogging_dq_comp.804 0 +motor.cogging_dq_comp.805 0 +motor.cogging_dq_comp.806 0 +motor.cogging_dq_comp.807 0 +motor.cogging_dq_comp.808 0 +motor.cogging_dq_comp.809 0 +motor.cogging_dq_comp.810 0 +motor.cogging_dq_comp.811 0 +motor.cogging_dq_comp.812 0 +motor.cogging_dq_comp.813 0 +motor.cogging_dq_comp.814 0 +motor.cogging_dq_comp.815 0 +motor.cogging_dq_comp.816 0 +motor.cogging_dq_comp.817 0 +motor.cogging_dq_comp.818 0 +motor.cogging_dq_comp.819 0 +motor.cogging_dq_comp.820 0 +motor.cogging_dq_comp.821 0 +motor.cogging_dq_comp.822 0 +motor.cogging_dq_comp.823 0 +motor.cogging_dq_comp.824 0 +motor.cogging_dq_comp.825 0 +motor.cogging_dq_comp.826 0 +motor.cogging_dq_comp.827 0 +motor.cogging_dq_comp.828 0 +motor.cogging_dq_comp.829 0 +motor.cogging_dq_comp.830 0 +motor.cogging_dq_comp.831 0 +motor.cogging_dq_comp.832 0 +motor.cogging_dq_comp.833 0 +motor.cogging_dq_comp.834 0 +motor.cogging_dq_comp.835 0 +motor.cogging_dq_comp.836 0 +motor.cogging_dq_comp.837 0 +motor.cogging_dq_comp.838 0 +motor.cogging_dq_comp.839 0 +motor.cogging_dq_comp.840 0 +motor.cogging_dq_comp.841 0 +motor.cogging_dq_comp.842 0 +motor.cogging_dq_comp.843 0 +motor.cogging_dq_comp.844 0 +motor.cogging_dq_comp.845 0 +motor.cogging_dq_comp.846 0 +motor.cogging_dq_comp.847 0 +motor.cogging_dq_comp.848 0 +motor.cogging_dq_comp.849 0 +motor.cogging_dq_comp.850 0 +motor.cogging_dq_comp.851 0 +motor.cogging_dq_comp.852 0 +motor.cogging_dq_comp.853 0 +motor.cogging_dq_comp.854 0 +motor.cogging_dq_comp.855 0 +motor.cogging_dq_comp.856 0 +motor.cogging_dq_comp.857 0 +motor.cogging_dq_comp.858 0 +motor.cogging_dq_comp.859 0 +motor.cogging_dq_comp.860 0 +motor.cogging_dq_comp.861 0 +motor.cogging_dq_comp.862 0 +motor.cogging_dq_comp.863 0 +motor.cogging_dq_comp.864 0 +motor.cogging_dq_comp.865 0 +motor.cogging_dq_comp.866 0 +motor.cogging_dq_comp.867 0 +motor.cogging_dq_comp.868 0 +motor.cogging_dq_comp.869 0 +motor.cogging_dq_comp.870 0 +motor.cogging_dq_comp.871 0 +motor.cogging_dq_comp.872 0 +motor.cogging_dq_comp.873 0 +motor.cogging_dq_comp.874 0 +motor.cogging_dq_comp.875 0 +motor.cogging_dq_comp.876 0 +motor.cogging_dq_comp.877 0 +motor.cogging_dq_comp.878 0 +motor.cogging_dq_comp.879 0 +motor.cogging_dq_comp.880 0 +motor.cogging_dq_comp.881 0 +motor.cogging_dq_comp.882 0 +motor.cogging_dq_comp.883 0 +motor.cogging_dq_comp.884 0 +motor.cogging_dq_comp.885 0 +motor.cogging_dq_comp.886 0 +motor.cogging_dq_comp.887 0 +motor.cogging_dq_comp.888 0 +motor.cogging_dq_comp.889 0 +motor.cogging_dq_comp.890 0 +motor.cogging_dq_comp.891 0 +motor.cogging_dq_comp.892 0 +motor.cogging_dq_comp.893 0 +motor.cogging_dq_comp.894 0 +motor.cogging_dq_comp.895 0 +motor.cogging_dq_comp.896 0 +motor.cogging_dq_comp.897 0 +motor.cogging_dq_comp.898 0 +motor.cogging_dq_comp.899 0 +motor.cogging_dq_comp.900 0 +motor.cogging_dq_comp.901 0 +motor.cogging_dq_comp.902 0 +motor.cogging_dq_comp.903 0 +motor.cogging_dq_comp.904 0 +motor.cogging_dq_comp.905 0 +motor.cogging_dq_comp.906 0 +motor.cogging_dq_comp.907 0 +motor.cogging_dq_comp.908 0 +motor.cogging_dq_comp.909 0 +motor.cogging_dq_comp.910 0 +motor.cogging_dq_comp.911 0 +motor.cogging_dq_comp.912 0 +motor.cogging_dq_comp.913 0 +motor.cogging_dq_comp.914 0 +motor.cogging_dq_comp.915 0 +motor.cogging_dq_comp.916 0 +motor.cogging_dq_comp.917 0 +motor.cogging_dq_comp.918 0 +motor.cogging_dq_comp.919 0 +motor.cogging_dq_comp.920 0 +motor.cogging_dq_comp.921 0 +motor.cogging_dq_comp.922 0 +motor.cogging_dq_comp.923 0 +motor.cogging_dq_comp.924 0 +motor.cogging_dq_comp.925 0 +motor.cogging_dq_comp.926 0 +motor.cogging_dq_comp.927 0 +motor.cogging_dq_comp.928 0 +motor.cogging_dq_comp.929 0 +motor.cogging_dq_comp.930 0 +motor.cogging_dq_comp.931 0 +motor.cogging_dq_comp.932 0 +motor.cogging_dq_comp.933 0 +motor.cogging_dq_comp.934 0 +motor.cogging_dq_comp.935 0 +motor.cogging_dq_comp.936 0 +motor.cogging_dq_comp.937 0 +motor.cogging_dq_comp.938 0 +motor.cogging_dq_comp.939 0 +motor.cogging_dq_comp.940 0 +motor.cogging_dq_comp.941 0 +motor.cogging_dq_comp.942 0 +motor.cogging_dq_comp.943 0 +motor.cogging_dq_comp.944 0 +motor.cogging_dq_comp.945 0 +motor.cogging_dq_comp.946 0 +motor.cogging_dq_comp.947 0 +motor.cogging_dq_comp.948 0 +motor.cogging_dq_comp.949 0 +motor.cogging_dq_comp.950 0 +motor.cogging_dq_comp.951 0 +motor.cogging_dq_comp.952 0 +motor.cogging_dq_comp.953 0 +motor.cogging_dq_comp.954 0 +motor.cogging_dq_comp.955 0 +motor.cogging_dq_comp.956 0 +motor.cogging_dq_comp.957 0 +motor.cogging_dq_comp.958 0 +motor.cogging_dq_comp.959 0 +motor.cogging_dq_comp.960 0 +motor.cogging_dq_comp.961 0 +motor.cogging_dq_comp.962 0 +motor.cogging_dq_comp.963 0 +motor.cogging_dq_comp.964 0 +motor.cogging_dq_comp.965 0 +motor.cogging_dq_comp.966 0 +motor.cogging_dq_comp.967 0 +motor.cogging_dq_comp.968 0 +motor.cogging_dq_comp.969 0 +motor.cogging_dq_comp.970 0 +motor.cogging_dq_comp.971 0 +motor.cogging_dq_comp.972 0 +motor.cogging_dq_comp.973 0 +motor.cogging_dq_comp.974 0 +motor.cogging_dq_comp.975 0 +motor.cogging_dq_comp.976 0 +motor.cogging_dq_comp.977 0 +motor.cogging_dq_comp.978 0 +motor.cogging_dq_comp.979 0 +motor.cogging_dq_comp.980 0 +motor.cogging_dq_comp.981 0 +motor.cogging_dq_comp.982 0 +motor.cogging_dq_comp.983 0 +motor.cogging_dq_comp.984 0 +motor.cogging_dq_comp.985 0 +motor.cogging_dq_comp.986 0 +motor.cogging_dq_comp.987 0 +motor.cogging_dq_comp.988 0 +motor.cogging_dq_comp.989 0 +motor.cogging_dq_comp.990 0 +motor.cogging_dq_comp.991 0 +motor.cogging_dq_comp.992 0 +motor.cogging_dq_comp.993 0 +motor.cogging_dq_comp.994 0 +motor.cogging_dq_comp.995 0 +motor.cogging_dq_comp.996 0 +motor.cogging_dq_comp.997 0 +motor.cogging_dq_comp.998 0 +motor.cogging_dq_comp.999 0 +motor.cogging_dq_comp.1000 0 +motor.cogging_dq_comp.1001 0 +motor.cogging_dq_comp.1002 0 +motor.cogging_dq_comp.1003 0 +motor.cogging_dq_comp.1004 0 +motor.cogging_dq_comp.1005 0 +motor.cogging_dq_comp.1006 0 +motor.cogging_dq_comp.1007 0 +motor.cogging_dq_comp.1008 0 +motor.cogging_dq_comp.1009 0 +motor.cogging_dq_comp.1010 0 +motor.cogging_dq_comp.1011 0 +motor.cogging_dq_comp.1012 0 +motor.cogging_dq_comp.1013 0 +motor.cogging_dq_comp.1014 0 +motor.cogging_dq_comp.1015 0 +motor.cogging_dq_comp.1016 0 +motor.cogging_dq_comp.1017 0 +motor.cogging_dq_comp.1018 0 +motor.cogging_dq_comp.1019 0 +motor.cogging_dq_comp.1020 0 +motor.cogging_dq_comp.1021 0 +motor.cogging_dq_comp.1022 0 +motor.cogging_dq_comp.1023 0 +drv8323_conf.dis_cpuv 0 +drv8323_conf.dis_gdf 0 +drv8323_conf.otw_rep 0 +drv8323_conf.pwm_mode 1 +drv8323_conf.pwm_1x_asynchronous 0 +drv8323_conf.pwm_1x_dir 0 +drv8323_conf.idrivep_hs_ma 100 +drv8323_conf.idriven_hs_ma 200 +drv8323_conf.cbc 1 +drv8323_conf.tdrive_ns 1000 +drv8323_conf.idrivep_ls_ma 100 +drv8323_conf.idriven_ls_ma 200 +drv8323_conf.tretry 0 +drv8323_conf.dead_time_ns 50 +drv8323_conf.ocp_mode 0 +drv8323_conf.ocp_deg_us 4 +drv8323_conf.vds_lvl_mv 700 +drv8323_conf.csa_fet 0 +drv8323_conf.vref_div 1 +drv8323_conf.ls_ref 0 +drv8323_conf.csa_gain 20 +drv8323_conf.dis_sen 0 +drv8323_conf.sen_lvl_mv 500 +servo.pwm_rate_hz 30000 +servo.i_gain 20.000000 +servo.current_sense_ohm 0.000500 +servo.pwm_comp_off 0.027000 +servo.pwm_comp_mag 0.005000 +servo.pwm_scale 1.000000 +servo.max_voltage 46.000000 +servo.max_power_W 450.000000 +servo.derate_temperature 50.000000 +servo.fault_temperature 75.000000 +servo.enable_motor_temperature 0 +servo.motor_derate_temperature 50.000000 +servo.motor_fault_temperature nan +servo.velocity_threshold 0.000000 +servo.position_derate 0.020000 +servo.adc_cur_cycles 2 +servo.adc_aux_cycles 47 +servo.pid_dq.kp 0.202691 +servo.pid_dq.ki 147.673920 +servo.pid_position.kp 0.500000 +servo.pid_position.ki 0.000000 +servo.pid_position.kd 0.050000 +servo.pid_position.iratelimit -1.000000 +servo.pid_position.ilimit 0.000000 +servo.pid_position.max_desired_rate 0.000000 +servo.pid_position.sign -1 +servo.current_feedforward 1.000000 +servo.bemf_feedforward 1.000000 +servo.default_velocity_limit nan +servo.default_accel_limit nan +servo.voltage_mode_control 0 +servo.fixed_voltage_mode 0 +servo.fixed_voltage_control_V 0.000000 +servo.max_position_slip 10.000000 +servo.default_timeout_s 0.100000 +servo.timeout_max_torque_Nm 5.000000 +servo.timeout_mode 12 +servo.flux_brake_min_voltage 43.500000 +servo.flux_brake_resistance_ohm 0.025000 +servo.max_current_A 7.500000 +servo.derate_current_A -20.000000 +servo.max_velocity 500.000000 +servo.max_velocity_derate 2.000000 +servo.cooldown_cycles 256 +servo.velocity_zero_capture_threshold 0.050000 +servo.emit_debug 0 +servopos.position_min nan +servopos.position_max nan +id.id 18 +can.prefix 0 + diff --git a/config/moteus/front_right.cfg b/config/moteus/front_right.cfg new file mode 100644 index 000000000..658a54eb5 --- /dev/null +++ b/config/moteus/front_right.cfg @@ -0,0 +1,1397 @@ +uuid.uuid.0 15 +uuid.uuid.1 46 +uuid.uuid.2 69 +uuid.uuid.3 9 +uuid.uuid.4 98 +uuid.uuid.5 199 +uuid.uuid.6 66 +uuid.uuid.7 137 +uuid.uuid.8 171 +uuid.uuid.9 14 +uuid.uuid.10 84 +uuid.uuid.11 252 +uuid.uuid.12 189 +uuid.uuid.13 133 +uuid.uuid.14 74 +uuid.uuid.15 234 +clock.hsitrim 64 +aux1.i2c.i2c_hz 400000 +aux1.i2c.i2c_mode 1 +aux1.i2c.pullup 0 +aux1.i2c.devices.0.type 0 +aux1.i2c.devices.0.address 64 +aux1.i2c.devices.0.poll_ms 10 +aux1.i2c.devices.1.type 0 +aux1.i2c.devices.1.address 64 +aux1.i2c.devices.1.poll_ms 10 +aux1.i2c.devices.2.type 0 +aux1.i2c.devices.2.address 64 +aux1.i2c.devices.2.poll_ms 10 +aux1.spi.mode 1 +aux1.spi.rate_hz 12000000 +aux1.spi.filter_us 64 +aux1.spi.bct 0 +aux1.uart.mode 0 +aux1.uart.baud_rate 115200 +aux1.uart.poll_rate_us 100 +aux1.uart.rs422 0 +aux1.uart.cui_amt21_address 84 +aux1.quadrature.enabled 0 +aux1.quadrature.cpr 16384 +aux1.hall.enabled 1 +aux1.hall.polarity 0 +aux1.index.enabled 0 +aux1.sine_cosine.enabled 0 +aux1.sine_cosine.common 1700 +aux1.i2c_startup_delay_ms 30 +aux1.pins.0.mode 6 +aux1.pins.0.pull 1 +aux1.pins.1.mode 6 +aux1.pins.1.pull 1 +aux1.pins.2.mode 6 +aux1.pins.2.pull 1 +aux1.pins.3.mode 0 +aux1.pins.3.pull 0 +aux1.pins.4.mode 0 +aux1.pins.4.pull 0 +aux2.i2c.i2c_hz 400000 +aux2.i2c.i2c_mode 1 +aux2.i2c.pullup 0 +aux2.i2c.devices.0.type 0 +aux2.i2c.devices.0.address 64 +aux2.i2c.devices.0.poll_ms 10 +aux2.i2c.devices.1.type 0 +aux2.i2c.devices.1.address 64 +aux2.i2c.devices.1.poll_ms 10 +aux2.i2c.devices.2.type 0 +aux2.i2c.devices.2.address 64 +aux2.i2c.devices.2.poll_ms 10 +aux2.spi.mode 0 +aux2.spi.rate_hz 12000000 +aux2.spi.filter_us 64 +aux2.spi.bct 0 +aux2.uart.mode 0 +aux2.uart.baud_rate 115200 +aux2.uart.poll_rate_us 100 +aux2.uart.rs422 0 +aux2.uart.cui_amt21_address 84 +aux2.quadrature.enabled 0 +aux2.quadrature.cpr 16384 +aux2.hall.enabled 0 +aux2.hall.polarity 0 +aux2.index.enabled 0 +aux2.sine_cosine.enabled 0 +aux2.sine_cosine.common 1700 +aux2.i2c_startup_delay_ms 30 +aux2.pins.0.mode 0 +aux2.pins.0.pull 0 +aux2.pins.1.mode 0 +aux2.pins.1.pull 0 +aux2.pins.2.mode 0 +aux2.pins.2.pull 0 +aux2.pins.3.mode 0 +aux2.pins.3.pull 0 +aux2.pins.4.mode 0 +aux2.pins.4.pull 0 +motor_position.sources.0.aux_number 1 +motor_position.sources.0.type 4 +motor_position.sources.0.i2c_device 0 +motor_position.sources.0.incremental_index -1 +motor_position.sources.0.cpr 84 +motor_position.sources.0.offset -1.000000 +motor_position.sources.0.sign 1 +motor_position.sources.0.debug_override -1 +motor_position.sources.0.reference 0 +motor_position.sources.0.pll_filter_hz 71.065834 +motor_position.sources.0.compensation_table.0 0.000000 +motor_position.sources.0.compensation_table.1 0.000000 +motor_position.sources.0.compensation_table.2 0.000000 +motor_position.sources.0.compensation_table.3 0.000000 +motor_position.sources.0.compensation_table.4 0.000000 +motor_position.sources.0.compensation_table.5 0.000000 +motor_position.sources.0.compensation_table.6 0.000000 +motor_position.sources.0.compensation_table.7 0.000000 +motor_position.sources.0.compensation_table.8 0.000000 +motor_position.sources.0.compensation_table.9 0.000000 +motor_position.sources.0.compensation_table.10 0.000000 +motor_position.sources.0.compensation_table.11 0.000000 +motor_position.sources.0.compensation_table.12 0.000000 +motor_position.sources.0.compensation_table.13 0.000000 +motor_position.sources.0.compensation_table.14 0.000000 +motor_position.sources.0.compensation_table.15 0.000000 +motor_position.sources.0.compensation_table.16 0.000000 +motor_position.sources.0.compensation_table.17 0.000000 +motor_position.sources.0.compensation_table.18 0.000000 +motor_position.sources.0.compensation_table.19 0.000000 +motor_position.sources.0.compensation_table.20 0.000000 +motor_position.sources.0.compensation_table.21 0.000000 +motor_position.sources.0.compensation_table.22 0.000000 +motor_position.sources.0.compensation_table.23 0.000000 +motor_position.sources.0.compensation_table.24 0.000000 +motor_position.sources.0.compensation_table.25 0.000000 +motor_position.sources.0.compensation_table.26 0.000000 +motor_position.sources.0.compensation_table.27 0.000000 +motor_position.sources.0.compensation_table.28 0.000000 +motor_position.sources.0.compensation_table.29 0.000000 +motor_position.sources.0.compensation_table.30 0.000000 +motor_position.sources.0.compensation_table.31 0.000000 +motor_position.sources.1.aux_number 1 +motor_position.sources.1.type 0 +motor_position.sources.1.i2c_device 0 +motor_position.sources.1.incremental_index -1 +motor_position.sources.1.cpr 84 +motor_position.sources.1.offset 0.000000 +motor_position.sources.1.sign 1 +motor_position.sources.1.debug_override -1 +motor_position.sources.1.reference 0 +motor_position.sources.1.pll_filter_hz 10.000000 +motor_position.sources.1.compensation_table.0 0.000000 +motor_position.sources.1.compensation_table.1 0.000000 +motor_position.sources.1.compensation_table.2 0.000000 +motor_position.sources.1.compensation_table.3 0.000000 +motor_position.sources.1.compensation_table.4 0.000000 +motor_position.sources.1.compensation_table.5 0.000000 +motor_position.sources.1.compensation_table.6 0.000000 +motor_position.sources.1.compensation_table.7 0.000000 +motor_position.sources.1.compensation_table.8 0.000000 +motor_position.sources.1.compensation_table.9 0.000000 +motor_position.sources.1.compensation_table.10 0.000000 +motor_position.sources.1.compensation_table.11 0.000000 +motor_position.sources.1.compensation_table.12 0.000000 +motor_position.sources.1.compensation_table.13 0.000000 +motor_position.sources.1.compensation_table.14 0.000000 +motor_position.sources.1.compensation_table.15 0.000000 +motor_position.sources.1.compensation_table.16 0.000000 +motor_position.sources.1.compensation_table.17 0.000000 +motor_position.sources.1.compensation_table.18 0.000000 +motor_position.sources.1.compensation_table.19 0.000000 +motor_position.sources.1.compensation_table.20 0.000000 +motor_position.sources.1.compensation_table.21 0.000000 +motor_position.sources.1.compensation_table.22 0.000000 +motor_position.sources.1.compensation_table.23 0.000000 +motor_position.sources.1.compensation_table.24 0.000000 +motor_position.sources.1.compensation_table.25 0.000000 +motor_position.sources.1.compensation_table.26 0.000000 +motor_position.sources.1.compensation_table.27 0.000000 +motor_position.sources.1.compensation_table.28 0.000000 +motor_position.sources.1.compensation_table.29 0.000000 +motor_position.sources.1.compensation_table.30 0.000000 +motor_position.sources.1.compensation_table.31 0.000000 +motor_position.sources.2.aux_number 1 +motor_position.sources.2.type 0 +motor_position.sources.2.i2c_device 0 +motor_position.sources.2.incremental_index -1 +motor_position.sources.2.cpr 16384 +motor_position.sources.2.offset 0.000000 +motor_position.sources.2.sign 1 +motor_position.sources.2.debug_override -1 +motor_position.sources.2.reference 0 +motor_position.sources.2.pll_filter_hz 400.000000 +motor_position.sources.2.compensation_table.0 0.000000 +motor_position.sources.2.compensation_table.1 0.000000 +motor_position.sources.2.compensation_table.2 0.000000 +motor_position.sources.2.compensation_table.3 0.000000 +motor_position.sources.2.compensation_table.4 0.000000 +motor_position.sources.2.compensation_table.5 0.000000 +motor_position.sources.2.compensation_table.6 0.000000 +motor_position.sources.2.compensation_table.7 0.000000 +motor_position.sources.2.compensation_table.8 0.000000 +motor_position.sources.2.compensation_table.9 0.000000 +motor_position.sources.2.compensation_table.10 0.000000 +motor_position.sources.2.compensation_table.11 0.000000 +motor_position.sources.2.compensation_table.12 0.000000 +motor_position.sources.2.compensation_table.13 0.000000 +motor_position.sources.2.compensation_table.14 0.000000 +motor_position.sources.2.compensation_table.15 0.000000 +motor_position.sources.2.compensation_table.16 0.000000 +motor_position.sources.2.compensation_table.17 0.000000 +motor_position.sources.2.compensation_table.18 0.000000 +motor_position.sources.2.compensation_table.19 0.000000 +motor_position.sources.2.compensation_table.20 0.000000 +motor_position.sources.2.compensation_table.21 0.000000 +motor_position.sources.2.compensation_table.22 0.000000 +motor_position.sources.2.compensation_table.23 0.000000 +motor_position.sources.2.compensation_table.24 0.000000 +motor_position.sources.2.compensation_table.25 0.000000 +motor_position.sources.2.compensation_table.26 0.000000 +motor_position.sources.2.compensation_table.27 0.000000 +motor_position.sources.2.compensation_table.28 0.000000 +motor_position.sources.2.compensation_table.29 0.000000 +motor_position.sources.2.compensation_table.30 0.000000 +motor_position.sources.2.compensation_table.31 0.000000 +motor_position.commutation_source 0 +motor_position.output.source 0 +motor_position.output.offset 0.000000 +motor_position.output.sign 1 +motor_position.output.reference_source -1 +motor_position.rotor_to_output_ratio 1.000000 +motor.poles 28 +motor.phase_invert 0 +motor.resistance_ohm 0.240511 +motor.v_per_hz 0.444322 +motor.offset.0 0.000000 +motor.offset.1 0.000000 +motor.offset.2 0.000000 +motor.offset.3 0.000000 +motor.offset.4 0.000000 +motor.offset.5 0.000000 +motor.offset.6 0.000000 +motor.offset.7 0.000000 +motor.offset.8 0.000000 +motor.offset.9 0.000000 +motor.offset.10 0.000000 +motor.offset.11 0.000000 +motor.offset.12 0.000000 +motor.offset.13 0.000000 +motor.offset.14 0.000000 +motor.offset.15 0.000000 +motor.offset.16 0.000000 +motor.offset.17 0.000000 +motor.offset.18 0.000000 +motor.offset.19 0.000000 +motor.offset.20 0.000000 +motor.offset.21 0.000000 +motor.offset.22 0.000000 +motor.offset.23 0.000000 +motor.offset.24 0.000000 +motor.offset.25 0.000000 +motor.offset.26 0.000000 +motor.offset.27 0.000000 +motor.offset.28 0.000000 +motor.offset.29 0.000000 +motor.offset.30 0.000000 +motor.offset.31 0.000000 +motor.offset.32 0.000000 +motor.offset.33 0.000000 +motor.offset.34 0.000000 +motor.offset.35 0.000000 +motor.offset.36 0.000000 +motor.offset.37 0.000000 +motor.offset.38 0.000000 +motor.offset.39 0.000000 +motor.offset.40 0.000000 +motor.offset.41 0.000000 +motor.offset.42 0.000000 +motor.offset.43 0.000000 +motor.offset.44 0.000000 +motor.offset.45 0.000000 +motor.offset.46 0.000000 +motor.offset.47 0.000000 +motor.offset.48 0.000000 +motor.offset.49 0.000000 +motor.offset.50 0.000000 +motor.offset.51 0.000000 +motor.offset.52 0.000000 +motor.offset.53 0.000000 +motor.offset.54 0.000000 +motor.offset.55 0.000000 +motor.offset.56 0.000000 +motor.offset.57 0.000000 +motor.offset.58 0.000000 +motor.offset.59 0.000000 +motor.offset.60 0.000000 +motor.offset.61 0.000000 +motor.offset.62 0.000000 +motor.offset.63 0.000000 +motor.rotation_current_cutoff_A 10000.000000 +motor.rotation_current_scale 0.050000 +motor.rotation_torque_scale 14.700000 +motor.cogging_dq_scale 0.000000 +motor.cogging_dq_comp.0 0 +motor.cogging_dq_comp.1 0 +motor.cogging_dq_comp.2 0 +motor.cogging_dq_comp.3 0 +motor.cogging_dq_comp.4 0 +motor.cogging_dq_comp.5 0 +motor.cogging_dq_comp.6 0 +motor.cogging_dq_comp.7 0 +motor.cogging_dq_comp.8 0 +motor.cogging_dq_comp.9 0 +motor.cogging_dq_comp.10 0 +motor.cogging_dq_comp.11 0 +motor.cogging_dq_comp.12 0 +motor.cogging_dq_comp.13 0 +motor.cogging_dq_comp.14 0 +motor.cogging_dq_comp.15 0 +motor.cogging_dq_comp.16 0 +motor.cogging_dq_comp.17 0 +motor.cogging_dq_comp.18 0 +motor.cogging_dq_comp.19 0 +motor.cogging_dq_comp.20 0 +motor.cogging_dq_comp.21 0 +motor.cogging_dq_comp.22 0 +motor.cogging_dq_comp.23 0 +motor.cogging_dq_comp.24 0 +motor.cogging_dq_comp.25 0 +motor.cogging_dq_comp.26 0 +motor.cogging_dq_comp.27 0 +motor.cogging_dq_comp.28 0 +motor.cogging_dq_comp.29 0 +motor.cogging_dq_comp.30 0 +motor.cogging_dq_comp.31 0 +motor.cogging_dq_comp.32 0 +motor.cogging_dq_comp.33 0 +motor.cogging_dq_comp.34 0 +motor.cogging_dq_comp.35 0 +motor.cogging_dq_comp.36 0 +motor.cogging_dq_comp.37 0 +motor.cogging_dq_comp.38 0 +motor.cogging_dq_comp.39 0 +motor.cogging_dq_comp.40 0 +motor.cogging_dq_comp.41 0 +motor.cogging_dq_comp.42 0 +motor.cogging_dq_comp.43 0 +motor.cogging_dq_comp.44 0 +motor.cogging_dq_comp.45 0 +motor.cogging_dq_comp.46 0 +motor.cogging_dq_comp.47 0 +motor.cogging_dq_comp.48 0 +motor.cogging_dq_comp.49 0 +motor.cogging_dq_comp.50 0 +motor.cogging_dq_comp.51 0 +motor.cogging_dq_comp.52 0 +motor.cogging_dq_comp.53 0 +motor.cogging_dq_comp.54 0 +motor.cogging_dq_comp.55 0 +motor.cogging_dq_comp.56 0 +motor.cogging_dq_comp.57 0 +motor.cogging_dq_comp.58 0 +motor.cogging_dq_comp.59 0 +motor.cogging_dq_comp.60 0 +motor.cogging_dq_comp.61 0 +motor.cogging_dq_comp.62 0 +motor.cogging_dq_comp.63 0 +motor.cogging_dq_comp.64 0 +motor.cogging_dq_comp.65 0 +motor.cogging_dq_comp.66 0 +motor.cogging_dq_comp.67 0 +motor.cogging_dq_comp.68 0 +motor.cogging_dq_comp.69 0 +motor.cogging_dq_comp.70 0 +motor.cogging_dq_comp.71 0 +motor.cogging_dq_comp.72 0 +motor.cogging_dq_comp.73 0 +motor.cogging_dq_comp.74 0 +motor.cogging_dq_comp.75 0 +motor.cogging_dq_comp.76 0 +motor.cogging_dq_comp.77 0 +motor.cogging_dq_comp.78 0 +motor.cogging_dq_comp.79 0 +motor.cogging_dq_comp.80 0 +motor.cogging_dq_comp.81 0 +motor.cogging_dq_comp.82 0 +motor.cogging_dq_comp.83 0 +motor.cogging_dq_comp.84 0 +motor.cogging_dq_comp.85 0 +motor.cogging_dq_comp.86 0 +motor.cogging_dq_comp.87 0 +motor.cogging_dq_comp.88 0 +motor.cogging_dq_comp.89 0 +motor.cogging_dq_comp.90 0 +motor.cogging_dq_comp.91 0 +motor.cogging_dq_comp.92 0 +motor.cogging_dq_comp.93 0 +motor.cogging_dq_comp.94 0 +motor.cogging_dq_comp.95 0 +motor.cogging_dq_comp.96 0 +motor.cogging_dq_comp.97 0 +motor.cogging_dq_comp.98 0 +motor.cogging_dq_comp.99 0 +motor.cogging_dq_comp.100 0 +motor.cogging_dq_comp.101 0 +motor.cogging_dq_comp.102 0 +motor.cogging_dq_comp.103 0 +motor.cogging_dq_comp.104 0 +motor.cogging_dq_comp.105 0 +motor.cogging_dq_comp.106 0 +motor.cogging_dq_comp.107 0 +motor.cogging_dq_comp.108 0 +motor.cogging_dq_comp.109 0 +motor.cogging_dq_comp.110 0 +motor.cogging_dq_comp.111 0 +motor.cogging_dq_comp.112 0 +motor.cogging_dq_comp.113 0 +motor.cogging_dq_comp.114 0 +motor.cogging_dq_comp.115 0 +motor.cogging_dq_comp.116 0 +motor.cogging_dq_comp.117 0 +motor.cogging_dq_comp.118 0 +motor.cogging_dq_comp.119 0 +motor.cogging_dq_comp.120 0 +motor.cogging_dq_comp.121 0 +motor.cogging_dq_comp.122 0 +motor.cogging_dq_comp.123 0 +motor.cogging_dq_comp.124 0 +motor.cogging_dq_comp.125 0 +motor.cogging_dq_comp.126 0 +motor.cogging_dq_comp.127 0 +motor.cogging_dq_comp.128 0 +motor.cogging_dq_comp.129 0 +motor.cogging_dq_comp.130 0 +motor.cogging_dq_comp.131 0 +motor.cogging_dq_comp.132 0 +motor.cogging_dq_comp.133 0 +motor.cogging_dq_comp.134 0 +motor.cogging_dq_comp.135 0 +motor.cogging_dq_comp.136 0 +motor.cogging_dq_comp.137 0 +motor.cogging_dq_comp.138 0 +motor.cogging_dq_comp.139 0 +motor.cogging_dq_comp.140 0 +motor.cogging_dq_comp.141 0 +motor.cogging_dq_comp.142 0 +motor.cogging_dq_comp.143 0 +motor.cogging_dq_comp.144 0 +motor.cogging_dq_comp.145 0 +motor.cogging_dq_comp.146 0 +motor.cogging_dq_comp.147 0 +motor.cogging_dq_comp.148 0 +motor.cogging_dq_comp.149 0 +motor.cogging_dq_comp.150 0 +motor.cogging_dq_comp.151 0 +motor.cogging_dq_comp.152 0 +motor.cogging_dq_comp.153 0 +motor.cogging_dq_comp.154 0 +motor.cogging_dq_comp.155 0 +motor.cogging_dq_comp.156 0 +motor.cogging_dq_comp.157 0 +motor.cogging_dq_comp.158 0 +motor.cogging_dq_comp.159 0 +motor.cogging_dq_comp.160 0 +motor.cogging_dq_comp.161 0 +motor.cogging_dq_comp.162 0 +motor.cogging_dq_comp.163 0 +motor.cogging_dq_comp.164 0 +motor.cogging_dq_comp.165 0 +motor.cogging_dq_comp.166 0 +motor.cogging_dq_comp.167 0 +motor.cogging_dq_comp.168 0 +motor.cogging_dq_comp.169 0 +motor.cogging_dq_comp.170 0 +motor.cogging_dq_comp.171 0 +motor.cogging_dq_comp.172 0 +motor.cogging_dq_comp.173 0 +motor.cogging_dq_comp.174 0 +motor.cogging_dq_comp.175 0 +motor.cogging_dq_comp.176 0 +motor.cogging_dq_comp.177 0 +motor.cogging_dq_comp.178 0 +motor.cogging_dq_comp.179 0 +motor.cogging_dq_comp.180 0 +motor.cogging_dq_comp.181 0 +motor.cogging_dq_comp.182 0 +motor.cogging_dq_comp.183 0 +motor.cogging_dq_comp.184 0 +motor.cogging_dq_comp.185 0 +motor.cogging_dq_comp.186 0 +motor.cogging_dq_comp.187 0 +motor.cogging_dq_comp.188 0 +motor.cogging_dq_comp.189 0 +motor.cogging_dq_comp.190 0 +motor.cogging_dq_comp.191 0 +motor.cogging_dq_comp.192 0 +motor.cogging_dq_comp.193 0 +motor.cogging_dq_comp.194 0 +motor.cogging_dq_comp.195 0 +motor.cogging_dq_comp.196 0 +motor.cogging_dq_comp.197 0 +motor.cogging_dq_comp.198 0 +motor.cogging_dq_comp.199 0 +motor.cogging_dq_comp.200 0 +motor.cogging_dq_comp.201 0 +motor.cogging_dq_comp.202 0 +motor.cogging_dq_comp.203 0 +motor.cogging_dq_comp.204 0 +motor.cogging_dq_comp.205 0 +motor.cogging_dq_comp.206 0 +motor.cogging_dq_comp.207 0 +motor.cogging_dq_comp.208 0 +motor.cogging_dq_comp.209 0 +motor.cogging_dq_comp.210 0 +motor.cogging_dq_comp.211 0 +motor.cogging_dq_comp.212 0 +motor.cogging_dq_comp.213 0 +motor.cogging_dq_comp.214 0 +motor.cogging_dq_comp.215 0 +motor.cogging_dq_comp.216 0 +motor.cogging_dq_comp.217 0 +motor.cogging_dq_comp.218 0 +motor.cogging_dq_comp.219 0 +motor.cogging_dq_comp.220 0 +motor.cogging_dq_comp.221 0 +motor.cogging_dq_comp.222 0 +motor.cogging_dq_comp.223 0 +motor.cogging_dq_comp.224 0 +motor.cogging_dq_comp.225 0 +motor.cogging_dq_comp.226 0 +motor.cogging_dq_comp.227 0 +motor.cogging_dq_comp.228 0 +motor.cogging_dq_comp.229 0 +motor.cogging_dq_comp.230 0 +motor.cogging_dq_comp.231 0 +motor.cogging_dq_comp.232 0 +motor.cogging_dq_comp.233 0 +motor.cogging_dq_comp.234 0 +motor.cogging_dq_comp.235 0 +motor.cogging_dq_comp.236 0 +motor.cogging_dq_comp.237 0 +motor.cogging_dq_comp.238 0 +motor.cogging_dq_comp.239 0 +motor.cogging_dq_comp.240 0 +motor.cogging_dq_comp.241 0 +motor.cogging_dq_comp.242 0 +motor.cogging_dq_comp.243 0 +motor.cogging_dq_comp.244 0 +motor.cogging_dq_comp.245 0 +motor.cogging_dq_comp.246 0 +motor.cogging_dq_comp.247 0 +motor.cogging_dq_comp.248 0 +motor.cogging_dq_comp.249 0 +motor.cogging_dq_comp.250 0 +motor.cogging_dq_comp.251 0 +motor.cogging_dq_comp.252 0 +motor.cogging_dq_comp.253 0 +motor.cogging_dq_comp.254 0 +motor.cogging_dq_comp.255 0 +motor.cogging_dq_comp.256 0 +motor.cogging_dq_comp.257 0 +motor.cogging_dq_comp.258 0 +motor.cogging_dq_comp.259 0 +motor.cogging_dq_comp.260 0 +motor.cogging_dq_comp.261 0 +motor.cogging_dq_comp.262 0 +motor.cogging_dq_comp.263 0 +motor.cogging_dq_comp.264 0 +motor.cogging_dq_comp.265 0 +motor.cogging_dq_comp.266 0 +motor.cogging_dq_comp.267 0 +motor.cogging_dq_comp.268 0 +motor.cogging_dq_comp.269 0 +motor.cogging_dq_comp.270 0 +motor.cogging_dq_comp.271 0 +motor.cogging_dq_comp.272 0 +motor.cogging_dq_comp.273 0 +motor.cogging_dq_comp.274 0 +motor.cogging_dq_comp.275 0 +motor.cogging_dq_comp.276 0 +motor.cogging_dq_comp.277 0 +motor.cogging_dq_comp.278 0 +motor.cogging_dq_comp.279 0 +motor.cogging_dq_comp.280 0 +motor.cogging_dq_comp.281 0 +motor.cogging_dq_comp.282 0 +motor.cogging_dq_comp.283 0 +motor.cogging_dq_comp.284 0 +motor.cogging_dq_comp.285 0 +motor.cogging_dq_comp.286 0 +motor.cogging_dq_comp.287 0 +motor.cogging_dq_comp.288 0 +motor.cogging_dq_comp.289 0 +motor.cogging_dq_comp.290 0 +motor.cogging_dq_comp.291 0 +motor.cogging_dq_comp.292 0 +motor.cogging_dq_comp.293 0 +motor.cogging_dq_comp.294 0 +motor.cogging_dq_comp.295 0 +motor.cogging_dq_comp.296 0 +motor.cogging_dq_comp.297 0 +motor.cogging_dq_comp.298 0 +motor.cogging_dq_comp.299 0 +motor.cogging_dq_comp.300 0 +motor.cogging_dq_comp.301 0 +motor.cogging_dq_comp.302 0 +motor.cogging_dq_comp.303 0 +motor.cogging_dq_comp.304 0 +motor.cogging_dq_comp.305 0 +motor.cogging_dq_comp.306 0 +motor.cogging_dq_comp.307 0 +motor.cogging_dq_comp.308 0 +motor.cogging_dq_comp.309 0 +motor.cogging_dq_comp.310 0 +motor.cogging_dq_comp.311 0 +motor.cogging_dq_comp.312 0 +motor.cogging_dq_comp.313 0 +motor.cogging_dq_comp.314 0 +motor.cogging_dq_comp.315 0 +motor.cogging_dq_comp.316 0 +motor.cogging_dq_comp.317 0 +motor.cogging_dq_comp.318 0 +motor.cogging_dq_comp.319 0 +motor.cogging_dq_comp.320 0 +motor.cogging_dq_comp.321 0 +motor.cogging_dq_comp.322 0 +motor.cogging_dq_comp.323 0 +motor.cogging_dq_comp.324 0 +motor.cogging_dq_comp.325 0 +motor.cogging_dq_comp.326 0 +motor.cogging_dq_comp.327 0 +motor.cogging_dq_comp.328 0 +motor.cogging_dq_comp.329 0 +motor.cogging_dq_comp.330 0 +motor.cogging_dq_comp.331 0 +motor.cogging_dq_comp.332 0 +motor.cogging_dq_comp.333 0 +motor.cogging_dq_comp.334 0 +motor.cogging_dq_comp.335 0 +motor.cogging_dq_comp.336 0 +motor.cogging_dq_comp.337 0 +motor.cogging_dq_comp.338 0 +motor.cogging_dq_comp.339 0 +motor.cogging_dq_comp.340 0 +motor.cogging_dq_comp.341 0 +motor.cogging_dq_comp.342 0 +motor.cogging_dq_comp.343 0 +motor.cogging_dq_comp.344 0 +motor.cogging_dq_comp.345 0 +motor.cogging_dq_comp.346 0 +motor.cogging_dq_comp.347 0 +motor.cogging_dq_comp.348 0 +motor.cogging_dq_comp.349 0 +motor.cogging_dq_comp.350 0 +motor.cogging_dq_comp.351 0 +motor.cogging_dq_comp.352 0 +motor.cogging_dq_comp.353 0 +motor.cogging_dq_comp.354 0 +motor.cogging_dq_comp.355 0 +motor.cogging_dq_comp.356 0 +motor.cogging_dq_comp.357 0 +motor.cogging_dq_comp.358 0 +motor.cogging_dq_comp.359 0 +motor.cogging_dq_comp.360 0 +motor.cogging_dq_comp.361 0 +motor.cogging_dq_comp.362 0 +motor.cogging_dq_comp.363 0 +motor.cogging_dq_comp.364 0 +motor.cogging_dq_comp.365 0 +motor.cogging_dq_comp.366 0 +motor.cogging_dq_comp.367 0 +motor.cogging_dq_comp.368 0 +motor.cogging_dq_comp.369 0 +motor.cogging_dq_comp.370 0 +motor.cogging_dq_comp.371 0 +motor.cogging_dq_comp.372 0 +motor.cogging_dq_comp.373 0 +motor.cogging_dq_comp.374 0 +motor.cogging_dq_comp.375 0 +motor.cogging_dq_comp.376 0 +motor.cogging_dq_comp.377 0 +motor.cogging_dq_comp.378 0 +motor.cogging_dq_comp.379 0 +motor.cogging_dq_comp.380 0 +motor.cogging_dq_comp.381 0 +motor.cogging_dq_comp.382 0 +motor.cogging_dq_comp.383 0 +motor.cogging_dq_comp.384 0 +motor.cogging_dq_comp.385 0 +motor.cogging_dq_comp.386 0 +motor.cogging_dq_comp.387 0 +motor.cogging_dq_comp.388 0 +motor.cogging_dq_comp.389 0 +motor.cogging_dq_comp.390 0 +motor.cogging_dq_comp.391 0 +motor.cogging_dq_comp.392 0 +motor.cogging_dq_comp.393 0 +motor.cogging_dq_comp.394 0 +motor.cogging_dq_comp.395 0 +motor.cogging_dq_comp.396 0 +motor.cogging_dq_comp.397 0 +motor.cogging_dq_comp.398 0 +motor.cogging_dq_comp.399 0 +motor.cogging_dq_comp.400 0 +motor.cogging_dq_comp.401 0 +motor.cogging_dq_comp.402 0 +motor.cogging_dq_comp.403 0 +motor.cogging_dq_comp.404 0 +motor.cogging_dq_comp.405 0 +motor.cogging_dq_comp.406 0 +motor.cogging_dq_comp.407 0 +motor.cogging_dq_comp.408 0 +motor.cogging_dq_comp.409 0 +motor.cogging_dq_comp.410 0 +motor.cogging_dq_comp.411 0 +motor.cogging_dq_comp.412 0 +motor.cogging_dq_comp.413 0 +motor.cogging_dq_comp.414 0 +motor.cogging_dq_comp.415 0 +motor.cogging_dq_comp.416 0 +motor.cogging_dq_comp.417 0 +motor.cogging_dq_comp.418 0 +motor.cogging_dq_comp.419 0 +motor.cogging_dq_comp.420 0 +motor.cogging_dq_comp.421 0 +motor.cogging_dq_comp.422 0 +motor.cogging_dq_comp.423 0 +motor.cogging_dq_comp.424 0 +motor.cogging_dq_comp.425 0 +motor.cogging_dq_comp.426 0 +motor.cogging_dq_comp.427 0 +motor.cogging_dq_comp.428 0 +motor.cogging_dq_comp.429 0 +motor.cogging_dq_comp.430 0 +motor.cogging_dq_comp.431 0 +motor.cogging_dq_comp.432 0 +motor.cogging_dq_comp.433 0 +motor.cogging_dq_comp.434 0 +motor.cogging_dq_comp.435 0 +motor.cogging_dq_comp.436 0 +motor.cogging_dq_comp.437 0 +motor.cogging_dq_comp.438 0 +motor.cogging_dq_comp.439 0 +motor.cogging_dq_comp.440 0 +motor.cogging_dq_comp.441 0 +motor.cogging_dq_comp.442 0 +motor.cogging_dq_comp.443 0 +motor.cogging_dq_comp.444 0 +motor.cogging_dq_comp.445 0 +motor.cogging_dq_comp.446 0 +motor.cogging_dq_comp.447 0 +motor.cogging_dq_comp.448 0 +motor.cogging_dq_comp.449 0 +motor.cogging_dq_comp.450 0 +motor.cogging_dq_comp.451 0 +motor.cogging_dq_comp.452 0 +motor.cogging_dq_comp.453 0 +motor.cogging_dq_comp.454 0 +motor.cogging_dq_comp.455 0 +motor.cogging_dq_comp.456 0 +motor.cogging_dq_comp.457 0 +motor.cogging_dq_comp.458 0 +motor.cogging_dq_comp.459 0 +motor.cogging_dq_comp.460 0 +motor.cogging_dq_comp.461 0 +motor.cogging_dq_comp.462 0 +motor.cogging_dq_comp.463 0 +motor.cogging_dq_comp.464 0 +motor.cogging_dq_comp.465 0 +motor.cogging_dq_comp.466 0 +motor.cogging_dq_comp.467 0 +motor.cogging_dq_comp.468 0 +motor.cogging_dq_comp.469 0 +motor.cogging_dq_comp.470 0 +motor.cogging_dq_comp.471 0 +motor.cogging_dq_comp.472 0 +motor.cogging_dq_comp.473 0 +motor.cogging_dq_comp.474 0 +motor.cogging_dq_comp.475 0 +motor.cogging_dq_comp.476 0 +motor.cogging_dq_comp.477 0 +motor.cogging_dq_comp.478 0 +motor.cogging_dq_comp.479 0 +motor.cogging_dq_comp.480 0 +motor.cogging_dq_comp.481 0 +motor.cogging_dq_comp.482 0 +motor.cogging_dq_comp.483 0 +motor.cogging_dq_comp.484 0 +motor.cogging_dq_comp.485 0 +motor.cogging_dq_comp.486 0 +motor.cogging_dq_comp.487 0 +motor.cogging_dq_comp.488 0 +motor.cogging_dq_comp.489 0 +motor.cogging_dq_comp.490 0 +motor.cogging_dq_comp.491 0 +motor.cogging_dq_comp.492 0 +motor.cogging_dq_comp.493 0 +motor.cogging_dq_comp.494 0 +motor.cogging_dq_comp.495 0 +motor.cogging_dq_comp.496 0 +motor.cogging_dq_comp.497 0 +motor.cogging_dq_comp.498 0 +motor.cogging_dq_comp.499 0 +motor.cogging_dq_comp.500 0 +motor.cogging_dq_comp.501 0 +motor.cogging_dq_comp.502 0 +motor.cogging_dq_comp.503 0 +motor.cogging_dq_comp.504 0 +motor.cogging_dq_comp.505 0 +motor.cogging_dq_comp.506 0 +motor.cogging_dq_comp.507 0 +motor.cogging_dq_comp.508 0 +motor.cogging_dq_comp.509 0 +motor.cogging_dq_comp.510 0 +motor.cogging_dq_comp.511 0 +motor.cogging_dq_comp.512 0 +motor.cogging_dq_comp.513 0 +motor.cogging_dq_comp.514 0 +motor.cogging_dq_comp.515 0 +motor.cogging_dq_comp.516 0 +motor.cogging_dq_comp.517 0 +motor.cogging_dq_comp.518 0 +motor.cogging_dq_comp.519 0 +motor.cogging_dq_comp.520 0 +motor.cogging_dq_comp.521 0 +motor.cogging_dq_comp.522 0 +motor.cogging_dq_comp.523 0 +motor.cogging_dq_comp.524 0 +motor.cogging_dq_comp.525 0 +motor.cogging_dq_comp.526 0 +motor.cogging_dq_comp.527 0 +motor.cogging_dq_comp.528 0 +motor.cogging_dq_comp.529 0 +motor.cogging_dq_comp.530 0 +motor.cogging_dq_comp.531 0 +motor.cogging_dq_comp.532 0 +motor.cogging_dq_comp.533 0 +motor.cogging_dq_comp.534 0 +motor.cogging_dq_comp.535 0 +motor.cogging_dq_comp.536 0 +motor.cogging_dq_comp.537 0 +motor.cogging_dq_comp.538 0 +motor.cogging_dq_comp.539 0 +motor.cogging_dq_comp.540 0 +motor.cogging_dq_comp.541 0 +motor.cogging_dq_comp.542 0 +motor.cogging_dq_comp.543 0 +motor.cogging_dq_comp.544 0 +motor.cogging_dq_comp.545 0 +motor.cogging_dq_comp.546 0 +motor.cogging_dq_comp.547 0 +motor.cogging_dq_comp.548 0 +motor.cogging_dq_comp.549 0 +motor.cogging_dq_comp.550 0 +motor.cogging_dq_comp.551 0 +motor.cogging_dq_comp.552 0 +motor.cogging_dq_comp.553 0 +motor.cogging_dq_comp.554 0 +motor.cogging_dq_comp.555 0 +motor.cogging_dq_comp.556 0 +motor.cogging_dq_comp.557 0 +motor.cogging_dq_comp.558 0 +motor.cogging_dq_comp.559 0 +motor.cogging_dq_comp.560 0 +motor.cogging_dq_comp.561 0 +motor.cogging_dq_comp.562 0 +motor.cogging_dq_comp.563 0 +motor.cogging_dq_comp.564 0 +motor.cogging_dq_comp.565 0 +motor.cogging_dq_comp.566 0 +motor.cogging_dq_comp.567 0 +motor.cogging_dq_comp.568 0 +motor.cogging_dq_comp.569 0 +motor.cogging_dq_comp.570 0 +motor.cogging_dq_comp.571 0 +motor.cogging_dq_comp.572 0 +motor.cogging_dq_comp.573 0 +motor.cogging_dq_comp.574 0 +motor.cogging_dq_comp.575 0 +motor.cogging_dq_comp.576 0 +motor.cogging_dq_comp.577 0 +motor.cogging_dq_comp.578 0 +motor.cogging_dq_comp.579 0 +motor.cogging_dq_comp.580 0 +motor.cogging_dq_comp.581 0 +motor.cogging_dq_comp.582 0 +motor.cogging_dq_comp.583 0 +motor.cogging_dq_comp.584 0 +motor.cogging_dq_comp.585 0 +motor.cogging_dq_comp.586 0 +motor.cogging_dq_comp.587 0 +motor.cogging_dq_comp.588 0 +motor.cogging_dq_comp.589 0 +motor.cogging_dq_comp.590 0 +motor.cogging_dq_comp.591 0 +motor.cogging_dq_comp.592 0 +motor.cogging_dq_comp.593 0 +motor.cogging_dq_comp.594 0 +motor.cogging_dq_comp.595 0 +motor.cogging_dq_comp.596 0 +motor.cogging_dq_comp.597 0 +motor.cogging_dq_comp.598 0 +motor.cogging_dq_comp.599 0 +motor.cogging_dq_comp.600 0 +motor.cogging_dq_comp.601 0 +motor.cogging_dq_comp.602 0 +motor.cogging_dq_comp.603 0 +motor.cogging_dq_comp.604 0 +motor.cogging_dq_comp.605 0 +motor.cogging_dq_comp.606 0 +motor.cogging_dq_comp.607 0 +motor.cogging_dq_comp.608 0 +motor.cogging_dq_comp.609 0 +motor.cogging_dq_comp.610 0 +motor.cogging_dq_comp.611 0 +motor.cogging_dq_comp.612 0 +motor.cogging_dq_comp.613 0 +motor.cogging_dq_comp.614 0 +motor.cogging_dq_comp.615 0 +motor.cogging_dq_comp.616 0 +motor.cogging_dq_comp.617 0 +motor.cogging_dq_comp.618 0 +motor.cogging_dq_comp.619 0 +motor.cogging_dq_comp.620 0 +motor.cogging_dq_comp.621 0 +motor.cogging_dq_comp.622 0 +motor.cogging_dq_comp.623 0 +motor.cogging_dq_comp.624 0 +motor.cogging_dq_comp.625 0 +motor.cogging_dq_comp.626 0 +motor.cogging_dq_comp.627 0 +motor.cogging_dq_comp.628 0 +motor.cogging_dq_comp.629 0 +motor.cogging_dq_comp.630 0 +motor.cogging_dq_comp.631 0 +motor.cogging_dq_comp.632 0 +motor.cogging_dq_comp.633 0 +motor.cogging_dq_comp.634 0 +motor.cogging_dq_comp.635 0 +motor.cogging_dq_comp.636 0 +motor.cogging_dq_comp.637 0 +motor.cogging_dq_comp.638 0 +motor.cogging_dq_comp.639 0 +motor.cogging_dq_comp.640 0 +motor.cogging_dq_comp.641 0 +motor.cogging_dq_comp.642 0 +motor.cogging_dq_comp.643 0 +motor.cogging_dq_comp.644 0 +motor.cogging_dq_comp.645 0 +motor.cogging_dq_comp.646 0 +motor.cogging_dq_comp.647 0 +motor.cogging_dq_comp.648 0 +motor.cogging_dq_comp.649 0 +motor.cogging_dq_comp.650 0 +motor.cogging_dq_comp.651 0 +motor.cogging_dq_comp.652 0 +motor.cogging_dq_comp.653 0 +motor.cogging_dq_comp.654 0 +motor.cogging_dq_comp.655 0 +motor.cogging_dq_comp.656 0 +motor.cogging_dq_comp.657 0 +motor.cogging_dq_comp.658 0 +motor.cogging_dq_comp.659 0 +motor.cogging_dq_comp.660 0 +motor.cogging_dq_comp.661 0 +motor.cogging_dq_comp.662 0 +motor.cogging_dq_comp.663 0 +motor.cogging_dq_comp.664 0 +motor.cogging_dq_comp.665 0 +motor.cogging_dq_comp.666 0 +motor.cogging_dq_comp.667 0 +motor.cogging_dq_comp.668 0 +motor.cogging_dq_comp.669 0 +motor.cogging_dq_comp.670 0 +motor.cogging_dq_comp.671 0 +motor.cogging_dq_comp.672 0 +motor.cogging_dq_comp.673 0 +motor.cogging_dq_comp.674 0 +motor.cogging_dq_comp.675 0 +motor.cogging_dq_comp.676 0 +motor.cogging_dq_comp.677 0 +motor.cogging_dq_comp.678 0 +motor.cogging_dq_comp.679 0 +motor.cogging_dq_comp.680 0 +motor.cogging_dq_comp.681 0 +motor.cogging_dq_comp.682 0 +motor.cogging_dq_comp.683 0 +motor.cogging_dq_comp.684 0 +motor.cogging_dq_comp.685 0 +motor.cogging_dq_comp.686 0 +motor.cogging_dq_comp.687 0 +motor.cogging_dq_comp.688 0 +motor.cogging_dq_comp.689 0 +motor.cogging_dq_comp.690 0 +motor.cogging_dq_comp.691 0 +motor.cogging_dq_comp.692 0 +motor.cogging_dq_comp.693 0 +motor.cogging_dq_comp.694 0 +motor.cogging_dq_comp.695 0 +motor.cogging_dq_comp.696 0 +motor.cogging_dq_comp.697 0 +motor.cogging_dq_comp.698 0 +motor.cogging_dq_comp.699 0 +motor.cogging_dq_comp.700 0 +motor.cogging_dq_comp.701 0 +motor.cogging_dq_comp.702 0 +motor.cogging_dq_comp.703 0 +motor.cogging_dq_comp.704 0 +motor.cogging_dq_comp.705 0 +motor.cogging_dq_comp.706 0 +motor.cogging_dq_comp.707 0 +motor.cogging_dq_comp.708 0 +motor.cogging_dq_comp.709 0 +motor.cogging_dq_comp.710 0 +motor.cogging_dq_comp.711 0 +motor.cogging_dq_comp.712 0 +motor.cogging_dq_comp.713 0 +motor.cogging_dq_comp.714 0 +motor.cogging_dq_comp.715 0 +motor.cogging_dq_comp.716 0 +motor.cogging_dq_comp.717 0 +motor.cogging_dq_comp.718 0 +motor.cogging_dq_comp.719 0 +motor.cogging_dq_comp.720 0 +motor.cogging_dq_comp.721 0 +motor.cogging_dq_comp.722 0 +motor.cogging_dq_comp.723 0 +motor.cogging_dq_comp.724 0 +motor.cogging_dq_comp.725 0 +motor.cogging_dq_comp.726 0 +motor.cogging_dq_comp.727 0 +motor.cogging_dq_comp.728 0 +motor.cogging_dq_comp.729 0 +motor.cogging_dq_comp.730 0 +motor.cogging_dq_comp.731 0 +motor.cogging_dq_comp.732 0 +motor.cogging_dq_comp.733 0 +motor.cogging_dq_comp.734 0 +motor.cogging_dq_comp.735 0 +motor.cogging_dq_comp.736 0 +motor.cogging_dq_comp.737 0 +motor.cogging_dq_comp.738 0 +motor.cogging_dq_comp.739 0 +motor.cogging_dq_comp.740 0 +motor.cogging_dq_comp.741 0 +motor.cogging_dq_comp.742 0 +motor.cogging_dq_comp.743 0 +motor.cogging_dq_comp.744 0 +motor.cogging_dq_comp.745 0 +motor.cogging_dq_comp.746 0 +motor.cogging_dq_comp.747 0 +motor.cogging_dq_comp.748 0 +motor.cogging_dq_comp.749 0 +motor.cogging_dq_comp.750 0 +motor.cogging_dq_comp.751 0 +motor.cogging_dq_comp.752 0 +motor.cogging_dq_comp.753 0 +motor.cogging_dq_comp.754 0 +motor.cogging_dq_comp.755 0 +motor.cogging_dq_comp.756 0 +motor.cogging_dq_comp.757 0 +motor.cogging_dq_comp.758 0 +motor.cogging_dq_comp.759 0 +motor.cogging_dq_comp.760 0 +motor.cogging_dq_comp.761 0 +motor.cogging_dq_comp.762 0 +motor.cogging_dq_comp.763 0 +motor.cogging_dq_comp.764 0 +motor.cogging_dq_comp.765 0 +motor.cogging_dq_comp.766 0 +motor.cogging_dq_comp.767 0 +motor.cogging_dq_comp.768 0 +motor.cogging_dq_comp.769 0 +motor.cogging_dq_comp.770 0 +motor.cogging_dq_comp.771 0 +motor.cogging_dq_comp.772 0 +motor.cogging_dq_comp.773 0 +motor.cogging_dq_comp.774 0 +motor.cogging_dq_comp.775 0 +motor.cogging_dq_comp.776 0 +motor.cogging_dq_comp.777 0 +motor.cogging_dq_comp.778 0 +motor.cogging_dq_comp.779 0 +motor.cogging_dq_comp.780 0 +motor.cogging_dq_comp.781 0 +motor.cogging_dq_comp.782 0 +motor.cogging_dq_comp.783 0 +motor.cogging_dq_comp.784 0 +motor.cogging_dq_comp.785 0 +motor.cogging_dq_comp.786 0 +motor.cogging_dq_comp.787 0 +motor.cogging_dq_comp.788 0 +motor.cogging_dq_comp.789 0 +motor.cogging_dq_comp.790 0 +motor.cogging_dq_comp.791 0 +motor.cogging_dq_comp.792 0 +motor.cogging_dq_comp.793 0 +motor.cogging_dq_comp.794 0 +motor.cogging_dq_comp.795 0 +motor.cogging_dq_comp.796 0 +motor.cogging_dq_comp.797 0 +motor.cogging_dq_comp.798 0 +motor.cogging_dq_comp.799 0 +motor.cogging_dq_comp.800 0 +motor.cogging_dq_comp.801 0 +motor.cogging_dq_comp.802 0 +motor.cogging_dq_comp.803 0 +motor.cogging_dq_comp.804 0 +motor.cogging_dq_comp.805 0 +motor.cogging_dq_comp.806 0 +motor.cogging_dq_comp.807 0 +motor.cogging_dq_comp.808 0 +motor.cogging_dq_comp.809 0 +motor.cogging_dq_comp.810 0 +motor.cogging_dq_comp.811 0 +motor.cogging_dq_comp.812 0 +motor.cogging_dq_comp.813 0 +motor.cogging_dq_comp.814 0 +motor.cogging_dq_comp.815 0 +motor.cogging_dq_comp.816 0 +motor.cogging_dq_comp.817 0 +motor.cogging_dq_comp.818 0 +motor.cogging_dq_comp.819 0 +motor.cogging_dq_comp.820 0 +motor.cogging_dq_comp.821 0 +motor.cogging_dq_comp.822 0 +motor.cogging_dq_comp.823 0 +motor.cogging_dq_comp.824 0 +motor.cogging_dq_comp.825 0 +motor.cogging_dq_comp.826 0 +motor.cogging_dq_comp.827 0 +motor.cogging_dq_comp.828 0 +motor.cogging_dq_comp.829 0 +motor.cogging_dq_comp.830 0 +motor.cogging_dq_comp.831 0 +motor.cogging_dq_comp.832 0 +motor.cogging_dq_comp.833 0 +motor.cogging_dq_comp.834 0 +motor.cogging_dq_comp.835 0 +motor.cogging_dq_comp.836 0 +motor.cogging_dq_comp.837 0 +motor.cogging_dq_comp.838 0 +motor.cogging_dq_comp.839 0 +motor.cogging_dq_comp.840 0 +motor.cogging_dq_comp.841 0 +motor.cogging_dq_comp.842 0 +motor.cogging_dq_comp.843 0 +motor.cogging_dq_comp.844 0 +motor.cogging_dq_comp.845 0 +motor.cogging_dq_comp.846 0 +motor.cogging_dq_comp.847 0 +motor.cogging_dq_comp.848 0 +motor.cogging_dq_comp.849 0 +motor.cogging_dq_comp.850 0 +motor.cogging_dq_comp.851 0 +motor.cogging_dq_comp.852 0 +motor.cogging_dq_comp.853 0 +motor.cogging_dq_comp.854 0 +motor.cogging_dq_comp.855 0 +motor.cogging_dq_comp.856 0 +motor.cogging_dq_comp.857 0 +motor.cogging_dq_comp.858 0 +motor.cogging_dq_comp.859 0 +motor.cogging_dq_comp.860 0 +motor.cogging_dq_comp.861 0 +motor.cogging_dq_comp.862 0 +motor.cogging_dq_comp.863 0 +motor.cogging_dq_comp.864 0 +motor.cogging_dq_comp.865 0 +motor.cogging_dq_comp.866 0 +motor.cogging_dq_comp.867 0 +motor.cogging_dq_comp.868 0 +motor.cogging_dq_comp.869 0 +motor.cogging_dq_comp.870 0 +motor.cogging_dq_comp.871 0 +motor.cogging_dq_comp.872 0 +motor.cogging_dq_comp.873 0 +motor.cogging_dq_comp.874 0 +motor.cogging_dq_comp.875 0 +motor.cogging_dq_comp.876 0 +motor.cogging_dq_comp.877 0 +motor.cogging_dq_comp.878 0 +motor.cogging_dq_comp.879 0 +motor.cogging_dq_comp.880 0 +motor.cogging_dq_comp.881 0 +motor.cogging_dq_comp.882 0 +motor.cogging_dq_comp.883 0 +motor.cogging_dq_comp.884 0 +motor.cogging_dq_comp.885 0 +motor.cogging_dq_comp.886 0 +motor.cogging_dq_comp.887 0 +motor.cogging_dq_comp.888 0 +motor.cogging_dq_comp.889 0 +motor.cogging_dq_comp.890 0 +motor.cogging_dq_comp.891 0 +motor.cogging_dq_comp.892 0 +motor.cogging_dq_comp.893 0 +motor.cogging_dq_comp.894 0 +motor.cogging_dq_comp.895 0 +motor.cogging_dq_comp.896 0 +motor.cogging_dq_comp.897 0 +motor.cogging_dq_comp.898 0 +motor.cogging_dq_comp.899 0 +motor.cogging_dq_comp.900 0 +motor.cogging_dq_comp.901 0 +motor.cogging_dq_comp.902 0 +motor.cogging_dq_comp.903 0 +motor.cogging_dq_comp.904 0 +motor.cogging_dq_comp.905 0 +motor.cogging_dq_comp.906 0 +motor.cogging_dq_comp.907 0 +motor.cogging_dq_comp.908 0 +motor.cogging_dq_comp.909 0 +motor.cogging_dq_comp.910 0 +motor.cogging_dq_comp.911 0 +motor.cogging_dq_comp.912 0 +motor.cogging_dq_comp.913 0 +motor.cogging_dq_comp.914 0 +motor.cogging_dq_comp.915 0 +motor.cogging_dq_comp.916 0 +motor.cogging_dq_comp.917 0 +motor.cogging_dq_comp.918 0 +motor.cogging_dq_comp.919 0 +motor.cogging_dq_comp.920 0 +motor.cogging_dq_comp.921 0 +motor.cogging_dq_comp.922 0 +motor.cogging_dq_comp.923 0 +motor.cogging_dq_comp.924 0 +motor.cogging_dq_comp.925 0 +motor.cogging_dq_comp.926 0 +motor.cogging_dq_comp.927 0 +motor.cogging_dq_comp.928 0 +motor.cogging_dq_comp.929 0 +motor.cogging_dq_comp.930 0 +motor.cogging_dq_comp.931 0 +motor.cogging_dq_comp.932 0 +motor.cogging_dq_comp.933 0 +motor.cogging_dq_comp.934 0 +motor.cogging_dq_comp.935 0 +motor.cogging_dq_comp.936 0 +motor.cogging_dq_comp.937 0 +motor.cogging_dq_comp.938 0 +motor.cogging_dq_comp.939 0 +motor.cogging_dq_comp.940 0 +motor.cogging_dq_comp.941 0 +motor.cogging_dq_comp.942 0 +motor.cogging_dq_comp.943 0 +motor.cogging_dq_comp.944 0 +motor.cogging_dq_comp.945 0 +motor.cogging_dq_comp.946 0 +motor.cogging_dq_comp.947 0 +motor.cogging_dq_comp.948 0 +motor.cogging_dq_comp.949 0 +motor.cogging_dq_comp.950 0 +motor.cogging_dq_comp.951 0 +motor.cogging_dq_comp.952 0 +motor.cogging_dq_comp.953 0 +motor.cogging_dq_comp.954 0 +motor.cogging_dq_comp.955 0 +motor.cogging_dq_comp.956 0 +motor.cogging_dq_comp.957 0 +motor.cogging_dq_comp.958 0 +motor.cogging_dq_comp.959 0 +motor.cogging_dq_comp.960 0 +motor.cogging_dq_comp.961 0 +motor.cogging_dq_comp.962 0 +motor.cogging_dq_comp.963 0 +motor.cogging_dq_comp.964 0 +motor.cogging_dq_comp.965 0 +motor.cogging_dq_comp.966 0 +motor.cogging_dq_comp.967 0 +motor.cogging_dq_comp.968 0 +motor.cogging_dq_comp.969 0 +motor.cogging_dq_comp.970 0 +motor.cogging_dq_comp.971 0 +motor.cogging_dq_comp.972 0 +motor.cogging_dq_comp.973 0 +motor.cogging_dq_comp.974 0 +motor.cogging_dq_comp.975 0 +motor.cogging_dq_comp.976 0 +motor.cogging_dq_comp.977 0 +motor.cogging_dq_comp.978 0 +motor.cogging_dq_comp.979 0 +motor.cogging_dq_comp.980 0 +motor.cogging_dq_comp.981 0 +motor.cogging_dq_comp.982 0 +motor.cogging_dq_comp.983 0 +motor.cogging_dq_comp.984 0 +motor.cogging_dq_comp.985 0 +motor.cogging_dq_comp.986 0 +motor.cogging_dq_comp.987 0 +motor.cogging_dq_comp.988 0 +motor.cogging_dq_comp.989 0 +motor.cogging_dq_comp.990 0 +motor.cogging_dq_comp.991 0 +motor.cogging_dq_comp.992 0 +motor.cogging_dq_comp.993 0 +motor.cogging_dq_comp.994 0 +motor.cogging_dq_comp.995 0 +motor.cogging_dq_comp.996 0 +motor.cogging_dq_comp.997 0 +motor.cogging_dq_comp.998 0 +motor.cogging_dq_comp.999 0 +motor.cogging_dq_comp.1000 0 +motor.cogging_dq_comp.1001 0 +motor.cogging_dq_comp.1002 0 +motor.cogging_dq_comp.1003 0 +motor.cogging_dq_comp.1004 0 +motor.cogging_dq_comp.1005 0 +motor.cogging_dq_comp.1006 0 +motor.cogging_dq_comp.1007 0 +motor.cogging_dq_comp.1008 0 +motor.cogging_dq_comp.1009 0 +motor.cogging_dq_comp.1010 0 +motor.cogging_dq_comp.1011 0 +motor.cogging_dq_comp.1012 0 +motor.cogging_dq_comp.1013 0 +motor.cogging_dq_comp.1014 0 +motor.cogging_dq_comp.1015 0 +motor.cogging_dq_comp.1016 0 +motor.cogging_dq_comp.1017 0 +motor.cogging_dq_comp.1018 0 +motor.cogging_dq_comp.1019 0 +motor.cogging_dq_comp.1020 0 +motor.cogging_dq_comp.1021 0 +motor.cogging_dq_comp.1022 0 +motor.cogging_dq_comp.1023 0 +drv8323_conf.dis_cpuv 0 +drv8323_conf.dis_gdf 0 +drv8323_conf.otw_rep 0 +drv8323_conf.pwm_mode 1 +drv8323_conf.pwm_1x_asynchronous 0 +drv8323_conf.pwm_1x_dir 0 +drv8323_conf.idrivep_hs_ma 100 +drv8323_conf.idriven_hs_ma 200 +drv8323_conf.cbc 1 +drv8323_conf.tdrive_ns 1000 +drv8323_conf.idrivep_ls_ma 100 +drv8323_conf.idriven_ls_ma 200 +drv8323_conf.tretry 0 +drv8323_conf.dead_time_ns 50 +drv8323_conf.ocp_mode 0 +drv8323_conf.ocp_deg_us 4 +drv8323_conf.vds_lvl_mv 700 +drv8323_conf.csa_fet 0 +drv8323_conf.vref_div 1 +drv8323_conf.ls_ref 0 +drv8323_conf.csa_gain 20 +drv8323_conf.dis_sen 0 +drv8323_conf.sen_lvl_mv 500 +servo.pwm_rate_hz 30000 +servo.i_gain 20.000000 +servo.current_sense_ohm 0.000500 +servo.pwm_comp_off 0.027000 +servo.pwm_comp_mag 0.005000 +servo.pwm_scale 1.000000 +servo.max_voltage 46.000000 +servo.max_power_W 450.000000 +servo.derate_temperature 50.000000 +servo.fault_temperature 75.000000 +servo.enable_motor_temperature 0 +servo.motor_derate_temperature 50.000000 +servo.motor_fault_temperature nan +servo.velocity_threshold 0.000000 +servo.position_derate 0.020000 +servo.adc_cur_cycles 2 +servo.adc_aux_cycles 47 +servo.pid_dq.kp 0.176827 +servo.pid_dq.ki 151.117355 +servo.pid_position.kp 0.500000 +servo.pid_position.ki 0.000000 +servo.pid_position.kd 0.050000 +servo.pid_position.iratelimit -1.000000 +servo.pid_position.ilimit 0.000000 +servo.pid_position.max_desired_rate 0.000000 +servo.pid_position.sign -1 +servo.current_feedforward 1.000000 +servo.bemf_feedforward 1.000000 +servo.default_velocity_limit nan +servo.default_accel_limit nan +servo.voltage_mode_control 0 +servo.fixed_voltage_mode 0 +servo.fixed_voltage_control_V 0.000000 +servo.max_position_slip 10.000000 +servo.default_timeout_s 0.100000 +servo.timeout_max_torque_Nm 5.000000 +servo.timeout_mode 12 +servo.flux_brake_min_voltage 43.500000 +servo.flux_brake_resistance_ohm 0.025000 +servo.max_current_A 4.000000 +servo.derate_current_A -20.000000 +servo.max_velocity 500.000000 +servo.max_velocity_derate 2.000000 +servo.cooldown_cycles 256 +servo.velocity_zero_capture_threshold 0.050000 +servo.emit_debug 0 +servopos.position_min nan +servopos.position_max nan +id.id 17 +can.prefix 0 + diff --git a/config/moteus/middle_left.cfg b/config/moteus/middle_left.cfg new file mode 100644 index 000000000..6b0689bc5 --- /dev/null +++ b/config/moteus/middle_left.cfg @@ -0,0 +1,1397 @@ +uuid.uuid.0 251 +uuid.uuid.1 136 +uuid.uuid.2 255 +uuid.uuid.3 85 +uuid.uuid.4 115 +uuid.uuid.5 82 +uuid.uuid.6 71 +uuid.uuid.7 65 +uuid.uuid.8 167 +uuid.uuid.9 42 +uuid.uuid.10 202 +uuid.uuid.11 217 +uuid.uuid.12 60 +uuid.uuid.13 130 +uuid.uuid.14 211 +uuid.uuid.15 64 +clock.hsitrim 64 +aux1.i2c.i2c_hz 400000 +aux1.i2c.i2c_mode 1 +aux1.i2c.pullup 0 +aux1.i2c.devices.0.type 0 +aux1.i2c.devices.0.address 64 +aux1.i2c.devices.0.poll_ms 10 +aux1.i2c.devices.1.type 0 +aux1.i2c.devices.1.address 64 +aux1.i2c.devices.1.poll_ms 10 +aux1.i2c.devices.2.type 0 +aux1.i2c.devices.2.address 64 +aux1.i2c.devices.2.poll_ms 10 +aux1.spi.mode 1 +aux1.spi.rate_hz 12000000 +aux1.spi.filter_us 64 +aux1.spi.bct 0 +aux1.uart.mode 0 +aux1.uart.baud_rate 115200 +aux1.uart.poll_rate_us 100 +aux1.uart.rs422 0 +aux1.uart.cui_amt21_address 84 +aux1.quadrature.enabled 0 +aux1.quadrature.cpr 16384 +aux1.hall.enabled 1 +aux1.hall.polarity 0 +aux1.index.enabled 0 +aux1.sine_cosine.enabled 0 +aux1.sine_cosine.common 1700 +aux1.i2c_startup_delay_ms 30 +aux1.pins.0.mode 6 +aux1.pins.0.pull 1 +aux1.pins.1.mode 6 +aux1.pins.1.pull 1 +aux1.pins.2.mode 6 +aux1.pins.2.pull 1 +aux1.pins.3.mode 0 +aux1.pins.3.pull 0 +aux1.pins.4.mode 0 +aux1.pins.4.pull 0 +aux2.i2c.i2c_hz 400000 +aux2.i2c.i2c_mode 1 +aux2.i2c.pullup 0 +aux2.i2c.devices.0.type 0 +aux2.i2c.devices.0.address 64 +aux2.i2c.devices.0.poll_ms 10 +aux2.i2c.devices.1.type 0 +aux2.i2c.devices.1.address 64 +aux2.i2c.devices.1.poll_ms 10 +aux2.i2c.devices.2.type 0 +aux2.i2c.devices.2.address 64 +aux2.i2c.devices.2.poll_ms 10 +aux2.spi.mode 1 +aux2.spi.rate_hz 12000000 +aux2.spi.filter_us 64 +aux2.spi.bct 0 +aux2.uart.mode 0 +aux2.uart.baud_rate 115200 +aux2.uart.poll_rate_us 100 +aux2.uart.rs422 0 +aux2.uart.cui_amt21_address 84 +aux2.quadrature.enabled 0 +aux2.quadrature.cpr 16384 +aux2.hall.enabled 0 +aux2.hall.polarity 0 +aux2.index.enabled 0 +aux2.sine_cosine.enabled 0 +aux2.sine_cosine.common 1700 +aux2.i2c_startup_delay_ms 30 +aux2.pins.0.mode 0 +aux2.pins.0.pull 0 +aux2.pins.1.mode 0 +aux2.pins.1.pull 0 +aux2.pins.2.mode 0 +aux2.pins.2.pull 0 +aux2.pins.3.mode 0 +aux2.pins.3.pull 0 +aux2.pins.4.mode 0 +aux2.pins.4.pull 0 +motor_position.sources.0.aux_number 1 +motor_position.sources.0.type 4 +motor_position.sources.0.i2c_device 0 +motor_position.sources.0.incremental_index -1 +motor_position.sources.0.cpr 84 +motor_position.sources.0.offset -5.000000 +motor_position.sources.0.sign 1 +motor_position.sources.0.debug_override -1 +motor_position.sources.0.reference 0 +motor_position.sources.0.pll_filter_hz 65.305252 +motor_position.sources.0.compensation_table.0 0.000000 +motor_position.sources.0.compensation_table.1 0.000000 +motor_position.sources.0.compensation_table.2 0.000000 +motor_position.sources.0.compensation_table.3 0.000000 +motor_position.sources.0.compensation_table.4 0.000000 +motor_position.sources.0.compensation_table.5 0.000000 +motor_position.sources.0.compensation_table.6 0.000000 +motor_position.sources.0.compensation_table.7 0.000000 +motor_position.sources.0.compensation_table.8 0.000000 +motor_position.sources.0.compensation_table.9 0.000000 +motor_position.sources.0.compensation_table.10 0.000000 +motor_position.sources.0.compensation_table.11 0.000000 +motor_position.sources.0.compensation_table.12 0.000000 +motor_position.sources.0.compensation_table.13 0.000000 +motor_position.sources.0.compensation_table.14 0.000000 +motor_position.sources.0.compensation_table.15 0.000000 +motor_position.sources.0.compensation_table.16 0.000000 +motor_position.sources.0.compensation_table.17 0.000000 +motor_position.sources.0.compensation_table.18 0.000000 +motor_position.sources.0.compensation_table.19 0.000000 +motor_position.sources.0.compensation_table.20 0.000000 +motor_position.sources.0.compensation_table.21 0.000000 +motor_position.sources.0.compensation_table.22 0.000000 +motor_position.sources.0.compensation_table.23 0.000000 +motor_position.sources.0.compensation_table.24 0.000000 +motor_position.sources.0.compensation_table.25 0.000000 +motor_position.sources.0.compensation_table.26 0.000000 +motor_position.sources.0.compensation_table.27 0.000000 +motor_position.sources.0.compensation_table.28 0.000000 +motor_position.sources.0.compensation_table.29 0.000000 +motor_position.sources.0.compensation_table.30 0.000000 +motor_position.sources.0.compensation_table.31 0.000000 +motor_position.sources.1.aux_number 1 +motor_position.sources.1.type 0 +motor_position.sources.1.i2c_device 0 +motor_position.sources.1.incremental_index -1 +motor_position.sources.1.cpr 16384 +motor_position.sources.1.offset 0.000000 +motor_position.sources.1.sign 1 +motor_position.sources.1.debug_override -1 +motor_position.sources.1.reference 0 +motor_position.sources.1.pll_filter_hz 400.000000 +motor_position.sources.1.compensation_table.0 0.000000 +motor_position.sources.1.compensation_table.1 0.000000 +motor_position.sources.1.compensation_table.2 0.000000 +motor_position.sources.1.compensation_table.3 0.000000 +motor_position.sources.1.compensation_table.4 0.000000 +motor_position.sources.1.compensation_table.5 0.000000 +motor_position.sources.1.compensation_table.6 0.000000 +motor_position.sources.1.compensation_table.7 0.000000 +motor_position.sources.1.compensation_table.8 0.000000 +motor_position.sources.1.compensation_table.9 0.000000 +motor_position.sources.1.compensation_table.10 0.000000 +motor_position.sources.1.compensation_table.11 0.000000 +motor_position.sources.1.compensation_table.12 0.000000 +motor_position.sources.1.compensation_table.13 0.000000 +motor_position.sources.1.compensation_table.14 0.000000 +motor_position.sources.1.compensation_table.15 0.000000 +motor_position.sources.1.compensation_table.16 0.000000 +motor_position.sources.1.compensation_table.17 0.000000 +motor_position.sources.1.compensation_table.18 0.000000 +motor_position.sources.1.compensation_table.19 0.000000 +motor_position.sources.1.compensation_table.20 0.000000 +motor_position.sources.1.compensation_table.21 0.000000 +motor_position.sources.1.compensation_table.22 0.000000 +motor_position.sources.1.compensation_table.23 0.000000 +motor_position.sources.1.compensation_table.24 0.000000 +motor_position.sources.1.compensation_table.25 0.000000 +motor_position.sources.1.compensation_table.26 0.000000 +motor_position.sources.1.compensation_table.27 0.000000 +motor_position.sources.1.compensation_table.28 0.000000 +motor_position.sources.1.compensation_table.29 0.000000 +motor_position.sources.1.compensation_table.30 0.000000 +motor_position.sources.1.compensation_table.31 0.000000 +motor_position.sources.2.aux_number 1 +motor_position.sources.2.type 0 +motor_position.sources.2.i2c_device 0 +motor_position.sources.2.incremental_index -1 +motor_position.sources.2.cpr 16384 +motor_position.sources.2.offset 0.000000 +motor_position.sources.2.sign 1 +motor_position.sources.2.debug_override -1 +motor_position.sources.2.reference 0 +motor_position.sources.2.pll_filter_hz 400.000000 +motor_position.sources.2.compensation_table.0 0.000000 +motor_position.sources.2.compensation_table.1 0.000000 +motor_position.sources.2.compensation_table.2 0.000000 +motor_position.sources.2.compensation_table.3 0.000000 +motor_position.sources.2.compensation_table.4 0.000000 +motor_position.sources.2.compensation_table.5 0.000000 +motor_position.sources.2.compensation_table.6 0.000000 +motor_position.sources.2.compensation_table.7 0.000000 +motor_position.sources.2.compensation_table.8 0.000000 +motor_position.sources.2.compensation_table.9 0.000000 +motor_position.sources.2.compensation_table.10 0.000000 +motor_position.sources.2.compensation_table.11 0.000000 +motor_position.sources.2.compensation_table.12 0.000000 +motor_position.sources.2.compensation_table.13 0.000000 +motor_position.sources.2.compensation_table.14 0.000000 +motor_position.sources.2.compensation_table.15 0.000000 +motor_position.sources.2.compensation_table.16 0.000000 +motor_position.sources.2.compensation_table.17 0.000000 +motor_position.sources.2.compensation_table.18 0.000000 +motor_position.sources.2.compensation_table.19 0.000000 +motor_position.sources.2.compensation_table.20 0.000000 +motor_position.sources.2.compensation_table.21 0.000000 +motor_position.sources.2.compensation_table.22 0.000000 +motor_position.sources.2.compensation_table.23 0.000000 +motor_position.sources.2.compensation_table.24 0.000000 +motor_position.sources.2.compensation_table.25 0.000000 +motor_position.sources.2.compensation_table.26 0.000000 +motor_position.sources.2.compensation_table.27 0.000000 +motor_position.sources.2.compensation_table.28 0.000000 +motor_position.sources.2.compensation_table.29 0.000000 +motor_position.sources.2.compensation_table.30 0.000000 +motor_position.sources.2.compensation_table.31 0.000000 +motor_position.commutation_source 0 +motor_position.output.source 0 +motor_position.output.offset 0.000000 +motor_position.output.sign -1 +motor_position.output.reference_source -1 +motor_position.rotor_to_output_ratio 1.000000 +motor.poles 28 +motor.phase_invert 0 +motor.resistance_ohm 0.248204 +motor.v_per_hz 0.338219 +motor.offset.0 0.000000 +motor.offset.1 0.000000 +motor.offset.2 0.000000 +motor.offset.3 0.000000 +motor.offset.4 0.000000 +motor.offset.5 0.000000 +motor.offset.6 0.000000 +motor.offset.7 0.000000 +motor.offset.8 0.000000 +motor.offset.9 0.000000 +motor.offset.10 0.000000 +motor.offset.11 0.000000 +motor.offset.12 0.000000 +motor.offset.13 0.000000 +motor.offset.14 0.000000 +motor.offset.15 0.000000 +motor.offset.16 0.000000 +motor.offset.17 0.000000 +motor.offset.18 0.000000 +motor.offset.19 0.000000 +motor.offset.20 0.000000 +motor.offset.21 0.000000 +motor.offset.22 0.000000 +motor.offset.23 0.000000 +motor.offset.24 0.000000 +motor.offset.25 0.000000 +motor.offset.26 0.000000 +motor.offset.27 0.000000 +motor.offset.28 0.000000 +motor.offset.29 0.000000 +motor.offset.30 0.000000 +motor.offset.31 0.000000 +motor.offset.32 0.000000 +motor.offset.33 0.000000 +motor.offset.34 0.000000 +motor.offset.35 0.000000 +motor.offset.36 0.000000 +motor.offset.37 0.000000 +motor.offset.38 0.000000 +motor.offset.39 0.000000 +motor.offset.40 0.000000 +motor.offset.41 0.000000 +motor.offset.42 0.000000 +motor.offset.43 0.000000 +motor.offset.44 0.000000 +motor.offset.45 0.000000 +motor.offset.46 0.000000 +motor.offset.47 0.000000 +motor.offset.48 0.000000 +motor.offset.49 0.000000 +motor.offset.50 0.000000 +motor.offset.51 0.000000 +motor.offset.52 0.000000 +motor.offset.53 0.000000 +motor.offset.54 0.000000 +motor.offset.55 0.000000 +motor.offset.56 0.000000 +motor.offset.57 0.000000 +motor.offset.58 0.000000 +motor.offset.59 0.000000 +motor.offset.60 0.000000 +motor.offset.61 0.000000 +motor.offset.62 0.000000 +motor.offset.63 0.000000 +motor.rotation_current_cutoff_A 10000.000000 +motor.rotation_current_scale 0.050000 +motor.rotation_torque_scale 14.700000 +motor.cogging_dq_scale 0.000000 +motor.cogging_dq_comp.0 0 +motor.cogging_dq_comp.1 0 +motor.cogging_dq_comp.2 0 +motor.cogging_dq_comp.3 0 +motor.cogging_dq_comp.4 0 +motor.cogging_dq_comp.5 0 +motor.cogging_dq_comp.6 0 +motor.cogging_dq_comp.7 0 +motor.cogging_dq_comp.8 0 +motor.cogging_dq_comp.9 0 +motor.cogging_dq_comp.10 0 +motor.cogging_dq_comp.11 0 +motor.cogging_dq_comp.12 0 +motor.cogging_dq_comp.13 0 +motor.cogging_dq_comp.14 0 +motor.cogging_dq_comp.15 0 +motor.cogging_dq_comp.16 0 +motor.cogging_dq_comp.17 0 +motor.cogging_dq_comp.18 0 +motor.cogging_dq_comp.19 0 +motor.cogging_dq_comp.20 0 +motor.cogging_dq_comp.21 0 +motor.cogging_dq_comp.22 0 +motor.cogging_dq_comp.23 0 +motor.cogging_dq_comp.24 0 +motor.cogging_dq_comp.25 0 +motor.cogging_dq_comp.26 0 +motor.cogging_dq_comp.27 0 +motor.cogging_dq_comp.28 0 +motor.cogging_dq_comp.29 0 +motor.cogging_dq_comp.30 0 +motor.cogging_dq_comp.31 0 +motor.cogging_dq_comp.32 0 +motor.cogging_dq_comp.33 0 +motor.cogging_dq_comp.34 0 +motor.cogging_dq_comp.35 0 +motor.cogging_dq_comp.36 0 +motor.cogging_dq_comp.37 0 +motor.cogging_dq_comp.38 0 +motor.cogging_dq_comp.39 0 +motor.cogging_dq_comp.40 0 +motor.cogging_dq_comp.41 0 +motor.cogging_dq_comp.42 0 +motor.cogging_dq_comp.43 0 +motor.cogging_dq_comp.44 0 +motor.cogging_dq_comp.45 0 +motor.cogging_dq_comp.46 0 +motor.cogging_dq_comp.47 0 +motor.cogging_dq_comp.48 0 +motor.cogging_dq_comp.49 0 +motor.cogging_dq_comp.50 0 +motor.cogging_dq_comp.51 0 +motor.cogging_dq_comp.52 0 +motor.cogging_dq_comp.53 0 +motor.cogging_dq_comp.54 0 +motor.cogging_dq_comp.55 0 +motor.cogging_dq_comp.56 0 +motor.cogging_dq_comp.57 0 +motor.cogging_dq_comp.58 0 +motor.cogging_dq_comp.59 0 +motor.cogging_dq_comp.60 0 +motor.cogging_dq_comp.61 0 +motor.cogging_dq_comp.62 0 +motor.cogging_dq_comp.63 0 +motor.cogging_dq_comp.64 0 +motor.cogging_dq_comp.65 0 +motor.cogging_dq_comp.66 0 +motor.cogging_dq_comp.67 0 +motor.cogging_dq_comp.68 0 +motor.cogging_dq_comp.69 0 +motor.cogging_dq_comp.70 0 +motor.cogging_dq_comp.71 0 +motor.cogging_dq_comp.72 0 +motor.cogging_dq_comp.73 0 +motor.cogging_dq_comp.74 0 +motor.cogging_dq_comp.75 0 +motor.cogging_dq_comp.76 0 +motor.cogging_dq_comp.77 0 +motor.cogging_dq_comp.78 0 +motor.cogging_dq_comp.79 0 +motor.cogging_dq_comp.80 0 +motor.cogging_dq_comp.81 0 +motor.cogging_dq_comp.82 0 +motor.cogging_dq_comp.83 0 +motor.cogging_dq_comp.84 0 +motor.cogging_dq_comp.85 0 +motor.cogging_dq_comp.86 0 +motor.cogging_dq_comp.87 0 +motor.cogging_dq_comp.88 0 +motor.cogging_dq_comp.89 0 +motor.cogging_dq_comp.90 0 +motor.cogging_dq_comp.91 0 +motor.cogging_dq_comp.92 0 +motor.cogging_dq_comp.93 0 +motor.cogging_dq_comp.94 0 +motor.cogging_dq_comp.95 0 +motor.cogging_dq_comp.96 0 +motor.cogging_dq_comp.97 0 +motor.cogging_dq_comp.98 0 +motor.cogging_dq_comp.99 0 +motor.cogging_dq_comp.100 0 +motor.cogging_dq_comp.101 0 +motor.cogging_dq_comp.102 0 +motor.cogging_dq_comp.103 0 +motor.cogging_dq_comp.104 0 +motor.cogging_dq_comp.105 0 +motor.cogging_dq_comp.106 0 +motor.cogging_dq_comp.107 0 +motor.cogging_dq_comp.108 0 +motor.cogging_dq_comp.109 0 +motor.cogging_dq_comp.110 0 +motor.cogging_dq_comp.111 0 +motor.cogging_dq_comp.112 0 +motor.cogging_dq_comp.113 0 +motor.cogging_dq_comp.114 0 +motor.cogging_dq_comp.115 0 +motor.cogging_dq_comp.116 0 +motor.cogging_dq_comp.117 0 +motor.cogging_dq_comp.118 0 +motor.cogging_dq_comp.119 0 +motor.cogging_dq_comp.120 0 +motor.cogging_dq_comp.121 0 +motor.cogging_dq_comp.122 0 +motor.cogging_dq_comp.123 0 +motor.cogging_dq_comp.124 0 +motor.cogging_dq_comp.125 0 +motor.cogging_dq_comp.126 0 +motor.cogging_dq_comp.127 0 +motor.cogging_dq_comp.128 0 +motor.cogging_dq_comp.129 0 +motor.cogging_dq_comp.130 0 +motor.cogging_dq_comp.131 0 +motor.cogging_dq_comp.132 0 +motor.cogging_dq_comp.133 0 +motor.cogging_dq_comp.134 0 +motor.cogging_dq_comp.135 0 +motor.cogging_dq_comp.136 0 +motor.cogging_dq_comp.137 0 +motor.cogging_dq_comp.138 0 +motor.cogging_dq_comp.139 0 +motor.cogging_dq_comp.140 0 +motor.cogging_dq_comp.141 0 +motor.cogging_dq_comp.142 0 +motor.cogging_dq_comp.143 0 +motor.cogging_dq_comp.144 0 +motor.cogging_dq_comp.145 0 +motor.cogging_dq_comp.146 0 +motor.cogging_dq_comp.147 0 +motor.cogging_dq_comp.148 0 +motor.cogging_dq_comp.149 0 +motor.cogging_dq_comp.150 0 +motor.cogging_dq_comp.151 0 +motor.cogging_dq_comp.152 0 +motor.cogging_dq_comp.153 0 +motor.cogging_dq_comp.154 0 +motor.cogging_dq_comp.155 0 +motor.cogging_dq_comp.156 0 +motor.cogging_dq_comp.157 0 +motor.cogging_dq_comp.158 0 +motor.cogging_dq_comp.159 0 +motor.cogging_dq_comp.160 0 +motor.cogging_dq_comp.161 0 +motor.cogging_dq_comp.162 0 +motor.cogging_dq_comp.163 0 +motor.cogging_dq_comp.164 0 +motor.cogging_dq_comp.165 0 +motor.cogging_dq_comp.166 0 +motor.cogging_dq_comp.167 0 +motor.cogging_dq_comp.168 0 +motor.cogging_dq_comp.169 0 +motor.cogging_dq_comp.170 0 +motor.cogging_dq_comp.171 0 +motor.cogging_dq_comp.172 0 +motor.cogging_dq_comp.173 0 +motor.cogging_dq_comp.174 0 +motor.cogging_dq_comp.175 0 +motor.cogging_dq_comp.176 0 +motor.cogging_dq_comp.177 0 +motor.cogging_dq_comp.178 0 +motor.cogging_dq_comp.179 0 +motor.cogging_dq_comp.180 0 +motor.cogging_dq_comp.181 0 +motor.cogging_dq_comp.182 0 +motor.cogging_dq_comp.183 0 +motor.cogging_dq_comp.184 0 +motor.cogging_dq_comp.185 0 +motor.cogging_dq_comp.186 0 +motor.cogging_dq_comp.187 0 +motor.cogging_dq_comp.188 0 +motor.cogging_dq_comp.189 0 +motor.cogging_dq_comp.190 0 +motor.cogging_dq_comp.191 0 +motor.cogging_dq_comp.192 0 +motor.cogging_dq_comp.193 0 +motor.cogging_dq_comp.194 0 +motor.cogging_dq_comp.195 0 +motor.cogging_dq_comp.196 0 +motor.cogging_dq_comp.197 0 +motor.cogging_dq_comp.198 0 +motor.cogging_dq_comp.199 0 +motor.cogging_dq_comp.200 0 +motor.cogging_dq_comp.201 0 +motor.cogging_dq_comp.202 0 +motor.cogging_dq_comp.203 0 +motor.cogging_dq_comp.204 0 +motor.cogging_dq_comp.205 0 +motor.cogging_dq_comp.206 0 +motor.cogging_dq_comp.207 0 +motor.cogging_dq_comp.208 0 +motor.cogging_dq_comp.209 0 +motor.cogging_dq_comp.210 0 +motor.cogging_dq_comp.211 0 +motor.cogging_dq_comp.212 0 +motor.cogging_dq_comp.213 0 +motor.cogging_dq_comp.214 0 +motor.cogging_dq_comp.215 0 +motor.cogging_dq_comp.216 0 +motor.cogging_dq_comp.217 0 +motor.cogging_dq_comp.218 0 +motor.cogging_dq_comp.219 0 +motor.cogging_dq_comp.220 0 +motor.cogging_dq_comp.221 0 +motor.cogging_dq_comp.222 0 +motor.cogging_dq_comp.223 0 +motor.cogging_dq_comp.224 0 +motor.cogging_dq_comp.225 0 +motor.cogging_dq_comp.226 0 +motor.cogging_dq_comp.227 0 +motor.cogging_dq_comp.228 0 +motor.cogging_dq_comp.229 0 +motor.cogging_dq_comp.230 0 +motor.cogging_dq_comp.231 0 +motor.cogging_dq_comp.232 0 +motor.cogging_dq_comp.233 0 +motor.cogging_dq_comp.234 0 +motor.cogging_dq_comp.235 0 +motor.cogging_dq_comp.236 0 +motor.cogging_dq_comp.237 0 +motor.cogging_dq_comp.238 0 +motor.cogging_dq_comp.239 0 +motor.cogging_dq_comp.240 0 +motor.cogging_dq_comp.241 0 +motor.cogging_dq_comp.242 0 +motor.cogging_dq_comp.243 0 +motor.cogging_dq_comp.244 0 +motor.cogging_dq_comp.245 0 +motor.cogging_dq_comp.246 0 +motor.cogging_dq_comp.247 0 +motor.cogging_dq_comp.248 0 +motor.cogging_dq_comp.249 0 +motor.cogging_dq_comp.250 0 +motor.cogging_dq_comp.251 0 +motor.cogging_dq_comp.252 0 +motor.cogging_dq_comp.253 0 +motor.cogging_dq_comp.254 0 +motor.cogging_dq_comp.255 0 +motor.cogging_dq_comp.256 0 +motor.cogging_dq_comp.257 0 +motor.cogging_dq_comp.258 0 +motor.cogging_dq_comp.259 0 +motor.cogging_dq_comp.260 0 +motor.cogging_dq_comp.261 0 +motor.cogging_dq_comp.262 0 +motor.cogging_dq_comp.263 0 +motor.cogging_dq_comp.264 0 +motor.cogging_dq_comp.265 0 +motor.cogging_dq_comp.266 0 +motor.cogging_dq_comp.267 0 +motor.cogging_dq_comp.268 0 +motor.cogging_dq_comp.269 0 +motor.cogging_dq_comp.270 0 +motor.cogging_dq_comp.271 0 +motor.cogging_dq_comp.272 0 +motor.cogging_dq_comp.273 0 +motor.cogging_dq_comp.274 0 +motor.cogging_dq_comp.275 0 +motor.cogging_dq_comp.276 0 +motor.cogging_dq_comp.277 0 +motor.cogging_dq_comp.278 0 +motor.cogging_dq_comp.279 0 +motor.cogging_dq_comp.280 0 +motor.cogging_dq_comp.281 0 +motor.cogging_dq_comp.282 0 +motor.cogging_dq_comp.283 0 +motor.cogging_dq_comp.284 0 +motor.cogging_dq_comp.285 0 +motor.cogging_dq_comp.286 0 +motor.cogging_dq_comp.287 0 +motor.cogging_dq_comp.288 0 +motor.cogging_dq_comp.289 0 +motor.cogging_dq_comp.290 0 +motor.cogging_dq_comp.291 0 +motor.cogging_dq_comp.292 0 +motor.cogging_dq_comp.293 0 +motor.cogging_dq_comp.294 0 +motor.cogging_dq_comp.295 0 +motor.cogging_dq_comp.296 0 +motor.cogging_dq_comp.297 0 +motor.cogging_dq_comp.298 0 +motor.cogging_dq_comp.299 0 +motor.cogging_dq_comp.300 0 +motor.cogging_dq_comp.301 0 +motor.cogging_dq_comp.302 0 +motor.cogging_dq_comp.303 0 +motor.cogging_dq_comp.304 0 +motor.cogging_dq_comp.305 0 +motor.cogging_dq_comp.306 0 +motor.cogging_dq_comp.307 0 +motor.cogging_dq_comp.308 0 +motor.cogging_dq_comp.309 0 +motor.cogging_dq_comp.310 0 +motor.cogging_dq_comp.311 0 +motor.cogging_dq_comp.312 0 +motor.cogging_dq_comp.313 0 +motor.cogging_dq_comp.314 0 +motor.cogging_dq_comp.315 0 +motor.cogging_dq_comp.316 0 +motor.cogging_dq_comp.317 0 +motor.cogging_dq_comp.318 0 +motor.cogging_dq_comp.319 0 +motor.cogging_dq_comp.320 0 +motor.cogging_dq_comp.321 0 +motor.cogging_dq_comp.322 0 +motor.cogging_dq_comp.323 0 +motor.cogging_dq_comp.324 0 +motor.cogging_dq_comp.325 0 +motor.cogging_dq_comp.326 0 +motor.cogging_dq_comp.327 0 +motor.cogging_dq_comp.328 0 +motor.cogging_dq_comp.329 0 +motor.cogging_dq_comp.330 0 +motor.cogging_dq_comp.331 0 +motor.cogging_dq_comp.332 0 +motor.cogging_dq_comp.333 0 +motor.cogging_dq_comp.334 0 +motor.cogging_dq_comp.335 0 +motor.cogging_dq_comp.336 0 +motor.cogging_dq_comp.337 0 +motor.cogging_dq_comp.338 0 +motor.cogging_dq_comp.339 0 +motor.cogging_dq_comp.340 0 +motor.cogging_dq_comp.341 0 +motor.cogging_dq_comp.342 0 +motor.cogging_dq_comp.343 0 +motor.cogging_dq_comp.344 0 +motor.cogging_dq_comp.345 0 +motor.cogging_dq_comp.346 0 +motor.cogging_dq_comp.347 0 +motor.cogging_dq_comp.348 0 +motor.cogging_dq_comp.349 0 +motor.cogging_dq_comp.350 0 +motor.cogging_dq_comp.351 0 +motor.cogging_dq_comp.352 0 +motor.cogging_dq_comp.353 0 +motor.cogging_dq_comp.354 0 +motor.cogging_dq_comp.355 0 +motor.cogging_dq_comp.356 0 +motor.cogging_dq_comp.357 0 +motor.cogging_dq_comp.358 0 +motor.cogging_dq_comp.359 0 +motor.cogging_dq_comp.360 0 +motor.cogging_dq_comp.361 0 +motor.cogging_dq_comp.362 0 +motor.cogging_dq_comp.363 0 +motor.cogging_dq_comp.364 0 +motor.cogging_dq_comp.365 0 +motor.cogging_dq_comp.366 0 +motor.cogging_dq_comp.367 0 +motor.cogging_dq_comp.368 0 +motor.cogging_dq_comp.369 0 +motor.cogging_dq_comp.370 0 +motor.cogging_dq_comp.371 0 +motor.cogging_dq_comp.372 0 +motor.cogging_dq_comp.373 0 +motor.cogging_dq_comp.374 0 +motor.cogging_dq_comp.375 0 +motor.cogging_dq_comp.376 0 +motor.cogging_dq_comp.377 0 +motor.cogging_dq_comp.378 0 +motor.cogging_dq_comp.379 0 +motor.cogging_dq_comp.380 0 +motor.cogging_dq_comp.381 0 +motor.cogging_dq_comp.382 0 +motor.cogging_dq_comp.383 0 +motor.cogging_dq_comp.384 0 +motor.cogging_dq_comp.385 0 +motor.cogging_dq_comp.386 0 +motor.cogging_dq_comp.387 0 +motor.cogging_dq_comp.388 0 +motor.cogging_dq_comp.389 0 +motor.cogging_dq_comp.390 0 +motor.cogging_dq_comp.391 0 +motor.cogging_dq_comp.392 0 +motor.cogging_dq_comp.393 0 +motor.cogging_dq_comp.394 0 +motor.cogging_dq_comp.395 0 +motor.cogging_dq_comp.396 0 +motor.cogging_dq_comp.397 0 +motor.cogging_dq_comp.398 0 +motor.cogging_dq_comp.399 0 +motor.cogging_dq_comp.400 0 +motor.cogging_dq_comp.401 0 +motor.cogging_dq_comp.402 0 +motor.cogging_dq_comp.403 0 +motor.cogging_dq_comp.404 0 +motor.cogging_dq_comp.405 0 +motor.cogging_dq_comp.406 0 +motor.cogging_dq_comp.407 0 +motor.cogging_dq_comp.408 0 +motor.cogging_dq_comp.409 0 +motor.cogging_dq_comp.410 0 +motor.cogging_dq_comp.411 0 +motor.cogging_dq_comp.412 0 +motor.cogging_dq_comp.413 0 +motor.cogging_dq_comp.414 0 +motor.cogging_dq_comp.415 0 +motor.cogging_dq_comp.416 0 +motor.cogging_dq_comp.417 0 +motor.cogging_dq_comp.418 0 +motor.cogging_dq_comp.419 0 +motor.cogging_dq_comp.420 0 +motor.cogging_dq_comp.421 0 +motor.cogging_dq_comp.422 0 +motor.cogging_dq_comp.423 0 +motor.cogging_dq_comp.424 0 +motor.cogging_dq_comp.425 0 +motor.cogging_dq_comp.426 0 +motor.cogging_dq_comp.427 0 +motor.cogging_dq_comp.428 0 +motor.cogging_dq_comp.429 0 +motor.cogging_dq_comp.430 0 +motor.cogging_dq_comp.431 0 +motor.cogging_dq_comp.432 0 +motor.cogging_dq_comp.433 0 +motor.cogging_dq_comp.434 0 +motor.cogging_dq_comp.435 0 +motor.cogging_dq_comp.436 0 +motor.cogging_dq_comp.437 0 +motor.cogging_dq_comp.438 0 +motor.cogging_dq_comp.439 0 +motor.cogging_dq_comp.440 0 +motor.cogging_dq_comp.441 0 +motor.cogging_dq_comp.442 0 +motor.cogging_dq_comp.443 0 +motor.cogging_dq_comp.444 0 +motor.cogging_dq_comp.445 0 +motor.cogging_dq_comp.446 0 +motor.cogging_dq_comp.447 0 +motor.cogging_dq_comp.448 0 +motor.cogging_dq_comp.449 0 +motor.cogging_dq_comp.450 0 +motor.cogging_dq_comp.451 0 +motor.cogging_dq_comp.452 0 +motor.cogging_dq_comp.453 0 +motor.cogging_dq_comp.454 0 +motor.cogging_dq_comp.455 0 +motor.cogging_dq_comp.456 0 +motor.cogging_dq_comp.457 0 +motor.cogging_dq_comp.458 0 +motor.cogging_dq_comp.459 0 +motor.cogging_dq_comp.460 0 +motor.cogging_dq_comp.461 0 +motor.cogging_dq_comp.462 0 +motor.cogging_dq_comp.463 0 +motor.cogging_dq_comp.464 0 +motor.cogging_dq_comp.465 0 +motor.cogging_dq_comp.466 0 +motor.cogging_dq_comp.467 0 +motor.cogging_dq_comp.468 0 +motor.cogging_dq_comp.469 0 +motor.cogging_dq_comp.470 0 +motor.cogging_dq_comp.471 0 +motor.cogging_dq_comp.472 0 +motor.cogging_dq_comp.473 0 +motor.cogging_dq_comp.474 0 +motor.cogging_dq_comp.475 0 +motor.cogging_dq_comp.476 0 +motor.cogging_dq_comp.477 0 +motor.cogging_dq_comp.478 0 +motor.cogging_dq_comp.479 0 +motor.cogging_dq_comp.480 0 +motor.cogging_dq_comp.481 0 +motor.cogging_dq_comp.482 0 +motor.cogging_dq_comp.483 0 +motor.cogging_dq_comp.484 0 +motor.cogging_dq_comp.485 0 +motor.cogging_dq_comp.486 0 +motor.cogging_dq_comp.487 0 +motor.cogging_dq_comp.488 0 +motor.cogging_dq_comp.489 0 +motor.cogging_dq_comp.490 0 +motor.cogging_dq_comp.491 0 +motor.cogging_dq_comp.492 0 +motor.cogging_dq_comp.493 0 +motor.cogging_dq_comp.494 0 +motor.cogging_dq_comp.495 0 +motor.cogging_dq_comp.496 0 +motor.cogging_dq_comp.497 0 +motor.cogging_dq_comp.498 0 +motor.cogging_dq_comp.499 0 +motor.cogging_dq_comp.500 0 +motor.cogging_dq_comp.501 0 +motor.cogging_dq_comp.502 0 +motor.cogging_dq_comp.503 0 +motor.cogging_dq_comp.504 0 +motor.cogging_dq_comp.505 0 +motor.cogging_dq_comp.506 0 +motor.cogging_dq_comp.507 0 +motor.cogging_dq_comp.508 0 +motor.cogging_dq_comp.509 0 +motor.cogging_dq_comp.510 0 +motor.cogging_dq_comp.511 0 +motor.cogging_dq_comp.512 0 +motor.cogging_dq_comp.513 0 +motor.cogging_dq_comp.514 0 +motor.cogging_dq_comp.515 0 +motor.cogging_dq_comp.516 0 +motor.cogging_dq_comp.517 0 +motor.cogging_dq_comp.518 0 +motor.cogging_dq_comp.519 0 +motor.cogging_dq_comp.520 0 +motor.cogging_dq_comp.521 0 +motor.cogging_dq_comp.522 0 +motor.cogging_dq_comp.523 0 +motor.cogging_dq_comp.524 0 +motor.cogging_dq_comp.525 0 +motor.cogging_dq_comp.526 0 +motor.cogging_dq_comp.527 0 +motor.cogging_dq_comp.528 0 +motor.cogging_dq_comp.529 0 +motor.cogging_dq_comp.530 0 +motor.cogging_dq_comp.531 0 +motor.cogging_dq_comp.532 0 +motor.cogging_dq_comp.533 0 +motor.cogging_dq_comp.534 0 +motor.cogging_dq_comp.535 0 +motor.cogging_dq_comp.536 0 +motor.cogging_dq_comp.537 0 +motor.cogging_dq_comp.538 0 +motor.cogging_dq_comp.539 0 +motor.cogging_dq_comp.540 0 +motor.cogging_dq_comp.541 0 +motor.cogging_dq_comp.542 0 +motor.cogging_dq_comp.543 0 +motor.cogging_dq_comp.544 0 +motor.cogging_dq_comp.545 0 +motor.cogging_dq_comp.546 0 +motor.cogging_dq_comp.547 0 +motor.cogging_dq_comp.548 0 +motor.cogging_dq_comp.549 0 +motor.cogging_dq_comp.550 0 +motor.cogging_dq_comp.551 0 +motor.cogging_dq_comp.552 0 +motor.cogging_dq_comp.553 0 +motor.cogging_dq_comp.554 0 +motor.cogging_dq_comp.555 0 +motor.cogging_dq_comp.556 0 +motor.cogging_dq_comp.557 0 +motor.cogging_dq_comp.558 0 +motor.cogging_dq_comp.559 0 +motor.cogging_dq_comp.560 0 +motor.cogging_dq_comp.561 0 +motor.cogging_dq_comp.562 0 +motor.cogging_dq_comp.563 0 +motor.cogging_dq_comp.564 0 +motor.cogging_dq_comp.565 0 +motor.cogging_dq_comp.566 0 +motor.cogging_dq_comp.567 0 +motor.cogging_dq_comp.568 0 +motor.cogging_dq_comp.569 0 +motor.cogging_dq_comp.570 0 +motor.cogging_dq_comp.571 0 +motor.cogging_dq_comp.572 0 +motor.cogging_dq_comp.573 0 +motor.cogging_dq_comp.574 0 +motor.cogging_dq_comp.575 0 +motor.cogging_dq_comp.576 0 +motor.cogging_dq_comp.577 0 +motor.cogging_dq_comp.578 0 +motor.cogging_dq_comp.579 0 +motor.cogging_dq_comp.580 0 +motor.cogging_dq_comp.581 0 +motor.cogging_dq_comp.582 0 +motor.cogging_dq_comp.583 0 +motor.cogging_dq_comp.584 0 +motor.cogging_dq_comp.585 0 +motor.cogging_dq_comp.586 0 +motor.cogging_dq_comp.587 0 +motor.cogging_dq_comp.588 0 +motor.cogging_dq_comp.589 0 +motor.cogging_dq_comp.590 0 +motor.cogging_dq_comp.591 0 +motor.cogging_dq_comp.592 0 +motor.cogging_dq_comp.593 0 +motor.cogging_dq_comp.594 0 +motor.cogging_dq_comp.595 0 +motor.cogging_dq_comp.596 0 +motor.cogging_dq_comp.597 0 +motor.cogging_dq_comp.598 0 +motor.cogging_dq_comp.599 0 +motor.cogging_dq_comp.600 0 +motor.cogging_dq_comp.601 0 +motor.cogging_dq_comp.602 0 +motor.cogging_dq_comp.603 0 +motor.cogging_dq_comp.604 0 +motor.cogging_dq_comp.605 0 +motor.cogging_dq_comp.606 0 +motor.cogging_dq_comp.607 0 +motor.cogging_dq_comp.608 0 +motor.cogging_dq_comp.609 0 +motor.cogging_dq_comp.610 0 +motor.cogging_dq_comp.611 0 +motor.cogging_dq_comp.612 0 +motor.cogging_dq_comp.613 0 +motor.cogging_dq_comp.614 0 +motor.cogging_dq_comp.615 0 +motor.cogging_dq_comp.616 0 +motor.cogging_dq_comp.617 0 +motor.cogging_dq_comp.618 0 +motor.cogging_dq_comp.619 0 +motor.cogging_dq_comp.620 0 +motor.cogging_dq_comp.621 0 +motor.cogging_dq_comp.622 0 +motor.cogging_dq_comp.623 0 +motor.cogging_dq_comp.624 0 +motor.cogging_dq_comp.625 0 +motor.cogging_dq_comp.626 0 +motor.cogging_dq_comp.627 0 +motor.cogging_dq_comp.628 0 +motor.cogging_dq_comp.629 0 +motor.cogging_dq_comp.630 0 +motor.cogging_dq_comp.631 0 +motor.cogging_dq_comp.632 0 +motor.cogging_dq_comp.633 0 +motor.cogging_dq_comp.634 0 +motor.cogging_dq_comp.635 0 +motor.cogging_dq_comp.636 0 +motor.cogging_dq_comp.637 0 +motor.cogging_dq_comp.638 0 +motor.cogging_dq_comp.639 0 +motor.cogging_dq_comp.640 0 +motor.cogging_dq_comp.641 0 +motor.cogging_dq_comp.642 0 +motor.cogging_dq_comp.643 0 +motor.cogging_dq_comp.644 0 +motor.cogging_dq_comp.645 0 +motor.cogging_dq_comp.646 0 +motor.cogging_dq_comp.647 0 +motor.cogging_dq_comp.648 0 +motor.cogging_dq_comp.649 0 +motor.cogging_dq_comp.650 0 +motor.cogging_dq_comp.651 0 +motor.cogging_dq_comp.652 0 +motor.cogging_dq_comp.653 0 +motor.cogging_dq_comp.654 0 +motor.cogging_dq_comp.655 0 +motor.cogging_dq_comp.656 0 +motor.cogging_dq_comp.657 0 +motor.cogging_dq_comp.658 0 +motor.cogging_dq_comp.659 0 +motor.cogging_dq_comp.660 0 +motor.cogging_dq_comp.661 0 +motor.cogging_dq_comp.662 0 +motor.cogging_dq_comp.663 0 +motor.cogging_dq_comp.664 0 +motor.cogging_dq_comp.665 0 +motor.cogging_dq_comp.666 0 +motor.cogging_dq_comp.667 0 +motor.cogging_dq_comp.668 0 +motor.cogging_dq_comp.669 0 +motor.cogging_dq_comp.670 0 +motor.cogging_dq_comp.671 0 +motor.cogging_dq_comp.672 0 +motor.cogging_dq_comp.673 0 +motor.cogging_dq_comp.674 0 +motor.cogging_dq_comp.675 0 +motor.cogging_dq_comp.676 0 +motor.cogging_dq_comp.677 0 +motor.cogging_dq_comp.678 0 +motor.cogging_dq_comp.679 0 +motor.cogging_dq_comp.680 0 +motor.cogging_dq_comp.681 0 +motor.cogging_dq_comp.682 0 +motor.cogging_dq_comp.683 0 +motor.cogging_dq_comp.684 0 +motor.cogging_dq_comp.685 0 +motor.cogging_dq_comp.686 0 +motor.cogging_dq_comp.687 0 +motor.cogging_dq_comp.688 0 +motor.cogging_dq_comp.689 0 +motor.cogging_dq_comp.690 0 +motor.cogging_dq_comp.691 0 +motor.cogging_dq_comp.692 0 +motor.cogging_dq_comp.693 0 +motor.cogging_dq_comp.694 0 +motor.cogging_dq_comp.695 0 +motor.cogging_dq_comp.696 0 +motor.cogging_dq_comp.697 0 +motor.cogging_dq_comp.698 0 +motor.cogging_dq_comp.699 0 +motor.cogging_dq_comp.700 0 +motor.cogging_dq_comp.701 0 +motor.cogging_dq_comp.702 0 +motor.cogging_dq_comp.703 0 +motor.cogging_dq_comp.704 0 +motor.cogging_dq_comp.705 0 +motor.cogging_dq_comp.706 0 +motor.cogging_dq_comp.707 0 +motor.cogging_dq_comp.708 0 +motor.cogging_dq_comp.709 0 +motor.cogging_dq_comp.710 0 +motor.cogging_dq_comp.711 0 +motor.cogging_dq_comp.712 0 +motor.cogging_dq_comp.713 0 +motor.cogging_dq_comp.714 0 +motor.cogging_dq_comp.715 0 +motor.cogging_dq_comp.716 0 +motor.cogging_dq_comp.717 0 +motor.cogging_dq_comp.718 0 +motor.cogging_dq_comp.719 0 +motor.cogging_dq_comp.720 0 +motor.cogging_dq_comp.721 0 +motor.cogging_dq_comp.722 0 +motor.cogging_dq_comp.723 0 +motor.cogging_dq_comp.724 0 +motor.cogging_dq_comp.725 0 +motor.cogging_dq_comp.726 0 +motor.cogging_dq_comp.727 0 +motor.cogging_dq_comp.728 0 +motor.cogging_dq_comp.729 0 +motor.cogging_dq_comp.730 0 +motor.cogging_dq_comp.731 0 +motor.cogging_dq_comp.732 0 +motor.cogging_dq_comp.733 0 +motor.cogging_dq_comp.734 0 +motor.cogging_dq_comp.735 0 +motor.cogging_dq_comp.736 0 +motor.cogging_dq_comp.737 0 +motor.cogging_dq_comp.738 0 +motor.cogging_dq_comp.739 0 +motor.cogging_dq_comp.740 0 +motor.cogging_dq_comp.741 0 +motor.cogging_dq_comp.742 0 +motor.cogging_dq_comp.743 0 +motor.cogging_dq_comp.744 0 +motor.cogging_dq_comp.745 0 +motor.cogging_dq_comp.746 0 +motor.cogging_dq_comp.747 0 +motor.cogging_dq_comp.748 0 +motor.cogging_dq_comp.749 0 +motor.cogging_dq_comp.750 0 +motor.cogging_dq_comp.751 0 +motor.cogging_dq_comp.752 0 +motor.cogging_dq_comp.753 0 +motor.cogging_dq_comp.754 0 +motor.cogging_dq_comp.755 0 +motor.cogging_dq_comp.756 0 +motor.cogging_dq_comp.757 0 +motor.cogging_dq_comp.758 0 +motor.cogging_dq_comp.759 0 +motor.cogging_dq_comp.760 0 +motor.cogging_dq_comp.761 0 +motor.cogging_dq_comp.762 0 +motor.cogging_dq_comp.763 0 +motor.cogging_dq_comp.764 0 +motor.cogging_dq_comp.765 0 +motor.cogging_dq_comp.766 0 +motor.cogging_dq_comp.767 0 +motor.cogging_dq_comp.768 0 +motor.cogging_dq_comp.769 0 +motor.cogging_dq_comp.770 0 +motor.cogging_dq_comp.771 0 +motor.cogging_dq_comp.772 0 +motor.cogging_dq_comp.773 0 +motor.cogging_dq_comp.774 0 +motor.cogging_dq_comp.775 0 +motor.cogging_dq_comp.776 0 +motor.cogging_dq_comp.777 0 +motor.cogging_dq_comp.778 0 +motor.cogging_dq_comp.779 0 +motor.cogging_dq_comp.780 0 +motor.cogging_dq_comp.781 0 +motor.cogging_dq_comp.782 0 +motor.cogging_dq_comp.783 0 +motor.cogging_dq_comp.784 0 +motor.cogging_dq_comp.785 0 +motor.cogging_dq_comp.786 0 +motor.cogging_dq_comp.787 0 +motor.cogging_dq_comp.788 0 +motor.cogging_dq_comp.789 0 +motor.cogging_dq_comp.790 0 +motor.cogging_dq_comp.791 0 +motor.cogging_dq_comp.792 0 +motor.cogging_dq_comp.793 0 +motor.cogging_dq_comp.794 0 +motor.cogging_dq_comp.795 0 +motor.cogging_dq_comp.796 0 +motor.cogging_dq_comp.797 0 +motor.cogging_dq_comp.798 0 +motor.cogging_dq_comp.799 0 +motor.cogging_dq_comp.800 0 +motor.cogging_dq_comp.801 0 +motor.cogging_dq_comp.802 0 +motor.cogging_dq_comp.803 0 +motor.cogging_dq_comp.804 0 +motor.cogging_dq_comp.805 0 +motor.cogging_dq_comp.806 0 +motor.cogging_dq_comp.807 0 +motor.cogging_dq_comp.808 0 +motor.cogging_dq_comp.809 0 +motor.cogging_dq_comp.810 0 +motor.cogging_dq_comp.811 0 +motor.cogging_dq_comp.812 0 +motor.cogging_dq_comp.813 0 +motor.cogging_dq_comp.814 0 +motor.cogging_dq_comp.815 0 +motor.cogging_dq_comp.816 0 +motor.cogging_dq_comp.817 0 +motor.cogging_dq_comp.818 0 +motor.cogging_dq_comp.819 0 +motor.cogging_dq_comp.820 0 +motor.cogging_dq_comp.821 0 +motor.cogging_dq_comp.822 0 +motor.cogging_dq_comp.823 0 +motor.cogging_dq_comp.824 0 +motor.cogging_dq_comp.825 0 +motor.cogging_dq_comp.826 0 +motor.cogging_dq_comp.827 0 +motor.cogging_dq_comp.828 0 +motor.cogging_dq_comp.829 0 +motor.cogging_dq_comp.830 0 +motor.cogging_dq_comp.831 0 +motor.cogging_dq_comp.832 0 +motor.cogging_dq_comp.833 0 +motor.cogging_dq_comp.834 0 +motor.cogging_dq_comp.835 0 +motor.cogging_dq_comp.836 0 +motor.cogging_dq_comp.837 0 +motor.cogging_dq_comp.838 0 +motor.cogging_dq_comp.839 0 +motor.cogging_dq_comp.840 0 +motor.cogging_dq_comp.841 0 +motor.cogging_dq_comp.842 0 +motor.cogging_dq_comp.843 0 +motor.cogging_dq_comp.844 0 +motor.cogging_dq_comp.845 0 +motor.cogging_dq_comp.846 0 +motor.cogging_dq_comp.847 0 +motor.cogging_dq_comp.848 0 +motor.cogging_dq_comp.849 0 +motor.cogging_dq_comp.850 0 +motor.cogging_dq_comp.851 0 +motor.cogging_dq_comp.852 0 +motor.cogging_dq_comp.853 0 +motor.cogging_dq_comp.854 0 +motor.cogging_dq_comp.855 0 +motor.cogging_dq_comp.856 0 +motor.cogging_dq_comp.857 0 +motor.cogging_dq_comp.858 0 +motor.cogging_dq_comp.859 0 +motor.cogging_dq_comp.860 0 +motor.cogging_dq_comp.861 0 +motor.cogging_dq_comp.862 0 +motor.cogging_dq_comp.863 0 +motor.cogging_dq_comp.864 0 +motor.cogging_dq_comp.865 0 +motor.cogging_dq_comp.866 0 +motor.cogging_dq_comp.867 0 +motor.cogging_dq_comp.868 0 +motor.cogging_dq_comp.869 0 +motor.cogging_dq_comp.870 0 +motor.cogging_dq_comp.871 0 +motor.cogging_dq_comp.872 0 +motor.cogging_dq_comp.873 0 +motor.cogging_dq_comp.874 0 +motor.cogging_dq_comp.875 0 +motor.cogging_dq_comp.876 0 +motor.cogging_dq_comp.877 0 +motor.cogging_dq_comp.878 0 +motor.cogging_dq_comp.879 0 +motor.cogging_dq_comp.880 0 +motor.cogging_dq_comp.881 0 +motor.cogging_dq_comp.882 0 +motor.cogging_dq_comp.883 0 +motor.cogging_dq_comp.884 0 +motor.cogging_dq_comp.885 0 +motor.cogging_dq_comp.886 0 +motor.cogging_dq_comp.887 0 +motor.cogging_dq_comp.888 0 +motor.cogging_dq_comp.889 0 +motor.cogging_dq_comp.890 0 +motor.cogging_dq_comp.891 0 +motor.cogging_dq_comp.892 0 +motor.cogging_dq_comp.893 0 +motor.cogging_dq_comp.894 0 +motor.cogging_dq_comp.895 0 +motor.cogging_dq_comp.896 0 +motor.cogging_dq_comp.897 0 +motor.cogging_dq_comp.898 0 +motor.cogging_dq_comp.899 0 +motor.cogging_dq_comp.900 0 +motor.cogging_dq_comp.901 0 +motor.cogging_dq_comp.902 0 +motor.cogging_dq_comp.903 0 +motor.cogging_dq_comp.904 0 +motor.cogging_dq_comp.905 0 +motor.cogging_dq_comp.906 0 +motor.cogging_dq_comp.907 0 +motor.cogging_dq_comp.908 0 +motor.cogging_dq_comp.909 0 +motor.cogging_dq_comp.910 0 +motor.cogging_dq_comp.911 0 +motor.cogging_dq_comp.912 0 +motor.cogging_dq_comp.913 0 +motor.cogging_dq_comp.914 0 +motor.cogging_dq_comp.915 0 +motor.cogging_dq_comp.916 0 +motor.cogging_dq_comp.917 0 +motor.cogging_dq_comp.918 0 +motor.cogging_dq_comp.919 0 +motor.cogging_dq_comp.920 0 +motor.cogging_dq_comp.921 0 +motor.cogging_dq_comp.922 0 +motor.cogging_dq_comp.923 0 +motor.cogging_dq_comp.924 0 +motor.cogging_dq_comp.925 0 +motor.cogging_dq_comp.926 0 +motor.cogging_dq_comp.927 0 +motor.cogging_dq_comp.928 0 +motor.cogging_dq_comp.929 0 +motor.cogging_dq_comp.930 0 +motor.cogging_dq_comp.931 0 +motor.cogging_dq_comp.932 0 +motor.cogging_dq_comp.933 0 +motor.cogging_dq_comp.934 0 +motor.cogging_dq_comp.935 0 +motor.cogging_dq_comp.936 0 +motor.cogging_dq_comp.937 0 +motor.cogging_dq_comp.938 0 +motor.cogging_dq_comp.939 0 +motor.cogging_dq_comp.940 0 +motor.cogging_dq_comp.941 0 +motor.cogging_dq_comp.942 0 +motor.cogging_dq_comp.943 0 +motor.cogging_dq_comp.944 0 +motor.cogging_dq_comp.945 0 +motor.cogging_dq_comp.946 0 +motor.cogging_dq_comp.947 0 +motor.cogging_dq_comp.948 0 +motor.cogging_dq_comp.949 0 +motor.cogging_dq_comp.950 0 +motor.cogging_dq_comp.951 0 +motor.cogging_dq_comp.952 0 +motor.cogging_dq_comp.953 0 +motor.cogging_dq_comp.954 0 +motor.cogging_dq_comp.955 0 +motor.cogging_dq_comp.956 0 +motor.cogging_dq_comp.957 0 +motor.cogging_dq_comp.958 0 +motor.cogging_dq_comp.959 0 +motor.cogging_dq_comp.960 0 +motor.cogging_dq_comp.961 0 +motor.cogging_dq_comp.962 0 +motor.cogging_dq_comp.963 0 +motor.cogging_dq_comp.964 0 +motor.cogging_dq_comp.965 0 +motor.cogging_dq_comp.966 0 +motor.cogging_dq_comp.967 0 +motor.cogging_dq_comp.968 0 +motor.cogging_dq_comp.969 0 +motor.cogging_dq_comp.970 0 +motor.cogging_dq_comp.971 0 +motor.cogging_dq_comp.972 0 +motor.cogging_dq_comp.973 0 +motor.cogging_dq_comp.974 0 +motor.cogging_dq_comp.975 0 +motor.cogging_dq_comp.976 0 +motor.cogging_dq_comp.977 0 +motor.cogging_dq_comp.978 0 +motor.cogging_dq_comp.979 0 +motor.cogging_dq_comp.980 0 +motor.cogging_dq_comp.981 0 +motor.cogging_dq_comp.982 0 +motor.cogging_dq_comp.983 0 +motor.cogging_dq_comp.984 0 +motor.cogging_dq_comp.985 0 +motor.cogging_dq_comp.986 0 +motor.cogging_dq_comp.987 0 +motor.cogging_dq_comp.988 0 +motor.cogging_dq_comp.989 0 +motor.cogging_dq_comp.990 0 +motor.cogging_dq_comp.991 0 +motor.cogging_dq_comp.992 0 +motor.cogging_dq_comp.993 0 +motor.cogging_dq_comp.994 0 +motor.cogging_dq_comp.995 0 +motor.cogging_dq_comp.996 0 +motor.cogging_dq_comp.997 0 +motor.cogging_dq_comp.998 0 +motor.cogging_dq_comp.999 0 +motor.cogging_dq_comp.1000 0 +motor.cogging_dq_comp.1001 0 +motor.cogging_dq_comp.1002 0 +motor.cogging_dq_comp.1003 0 +motor.cogging_dq_comp.1004 0 +motor.cogging_dq_comp.1005 0 +motor.cogging_dq_comp.1006 0 +motor.cogging_dq_comp.1007 0 +motor.cogging_dq_comp.1008 0 +motor.cogging_dq_comp.1009 0 +motor.cogging_dq_comp.1010 0 +motor.cogging_dq_comp.1011 0 +motor.cogging_dq_comp.1012 0 +motor.cogging_dq_comp.1013 0 +motor.cogging_dq_comp.1014 0 +motor.cogging_dq_comp.1015 0 +motor.cogging_dq_comp.1016 0 +motor.cogging_dq_comp.1017 0 +motor.cogging_dq_comp.1018 0 +motor.cogging_dq_comp.1019 0 +motor.cogging_dq_comp.1020 0 +motor.cogging_dq_comp.1021 0 +motor.cogging_dq_comp.1022 0 +motor.cogging_dq_comp.1023 0 +drv8323_conf.dis_cpuv 0 +drv8323_conf.dis_gdf 0 +drv8323_conf.otw_rep 0 +drv8323_conf.pwm_mode 1 +drv8323_conf.pwm_1x_asynchronous 0 +drv8323_conf.pwm_1x_dir 0 +drv8323_conf.idrivep_hs_ma 100 +drv8323_conf.idriven_hs_ma 200 +drv8323_conf.cbc 1 +drv8323_conf.tdrive_ns 1000 +drv8323_conf.idrivep_ls_ma 100 +drv8323_conf.idriven_ls_ma 200 +drv8323_conf.tretry 0 +drv8323_conf.dead_time_ns 50 +drv8323_conf.ocp_mode 0 +drv8323_conf.ocp_deg_us 4 +drv8323_conf.vds_lvl_mv 700 +drv8323_conf.csa_fet 0 +drv8323_conf.vref_div 1 +drv8323_conf.ls_ref 0 +drv8323_conf.csa_gain 20 +drv8323_conf.dis_sen 0 +drv8323_conf.sen_lvl_mv 500 +servo.pwm_rate_hz 30000 +servo.i_gain 20.000000 +servo.current_sense_ohm 0.000500 +servo.pwm_comp_off 0.027000 +servo.pwm_comp_mag 0.005000 +servo.pwm_scale 1.000000 +servo.max_voltage 46.000000 +servo.max_power_W 450.000000 +servo.derate_temperature 50.000000 +servo.fault_temperature 75.000000 +servo.enable_motor_temperature 0 +servo.motor_derate_temperature 50.000000 +servo.motor_fault_temperature nan +servo.velocity_threshold 0.000000 +servo.position_derate 0.020000 +servo.adc_cur_cycles 2 +servo.adc_aux_cycles 47 +servo.pid_dq.kp 0.192425 +servo.pid_dq.ki 155.951324 +servo.pid_position.kp 0.500000 +servo.pid_position.ki 0.000000 +servo.pid_position.kd 0.050000 +servo.pid_position.iratelimit -1.000000 +servo.pid_position.ilimit 0.000000 +servo.pid_position.max_desired_rate 0.000000 +servo.pid_position.sign -1 +servo.current_feedforward 1.000000 +servo.bemf_feedforward 1.000000 +servo.default_velocity_limit nan +servo.default_accel_limit nan +servo.voltage_mode_control 0 +servo.fixed_voltage_mode 0 +servo.fixed_voltage_control_V 0.000000 +servo.max_position_slip 10.000000 +servo.default_timeout_s 0.100000 +servo.timeout_max_torque_Nm 5.000000 +servo.timeout_mode 12 +servo.flux_brake_min_voltage 43.500000 +servo.flux_brake_resistance_ohm 0.025000 +servo.max_current_A 7.500000 +servo.derate_current_A -20.000000 +servo.max_velocity 45.000000 +servo.max_velocity_derate 2.000000 +servo.cooldown_cycles 256 +servo.velocity_zero_capture_threshold 0.050000 +servo.emit_debug 0 +servopos.position_min nan +servopos.position_max nan +id.id 20 +can.prefix 0 + diff --git a/config/moteus/middle_right.cfg b/config/moteus/middle_right.cfg new file mode 100644 index 000000000..c8a4cf73c --- /dev/null +++ b/config/moteus/middle_right.cfg @@ -0,0 +1,1397 @@ +uuid.uuid.0 105 +uuid.uuid.1 13 +uuid.uuid.2 118 +uuid.uuid.3 61 +uuid.uuid.4 27 +uuid.uuid.5 255 +uuid.uuid.6 74 +uuid.uuid.7 237 +uuid.uuid.8 130 +uuid.uuid.9 123 +uuid.uuid.10 70 +uuid.uuid.11 92 +uuid.uuid.12 86 +uuid.uuid.13 59 +uuid.uuid.14 11 +uuid.uuid.15 26 +clock.hsitrim 64 +aux1.i2c.i2c_hz 400000 +aux1.i2c.i2c_mode 1 +aux1.i2c.pullup 0 +aux1.i2c.devices.0.type 0 +aux1.i2c.devices.0.address 64 +aux1.i2c.devices.0.poll_ms 10 +aux1.i2c.devices.1.type 0 +aux1.i2c.devices.1.address 64 +aux1.i2c.devices.1.poll_ms 10 +aux1.i2c.devices.2.type 0 +aux1.i2c.devices.2.address 64 +aux1.i2c.devices.2.poll_ms 10 +aux1.spi.mode 1 +aux1.spi.rate_hz 12000000 +aux1.spi.filter_us 64 +aux1.spi.bct 0 +aux1.uart.mode 0 +aux1.uart.baud_rate 115200 +aux1.uart.poll_rate_us 100 +aux1.uart.rs422 0 +aux1.uart.cui_amt21_address 84 +aux1.quadrature.enabled 0 +aux1.quadrature.cpr 16384 +aux1.hall.enabled 1 +aux1.hall.polarity 0 +aux1.index.enabled 0 +aux1.sine_cosine.enabled 0 +aux1.sine_cosine.common 1700 +aux1.i2c_startup_delay_ms 30 +aux1.pins.0.mode 6 +aux1.pins.0.pull 1 +aux1.pins.1.mode 6 +aux1.pins.1.pull 1 +aux1.pins.2.mode 6 +aux1.pins.2.pull 1 +aux1.pins.3.mode 0 +aux1.pins.3.pull 0 +aux1.pins.4.mode 0 +aux1.pins.4.pull 0 +aux2.i2c.i2c_hz 400000 +aux2.i2c.i2c_mode 1 +aux2.i2c.pullup 0 +aux2.i2c.devices.0.type 0 +aux2.i2c.devices.0.address 64 +aux2.i2c.devices.0.poll_ms 10 +aux2.i2c.devices.1.type 0 +aux2.i2c.devices.1.address 64 +aux2.i2c.devices.1.poll_ms 10 +aux2.i2c.devices.2.type 0 +aux2.i2c.devices.2.address 64 +aux2.i2c.devices.2.poll_ms 10 +aux2.spi.mode 0 +aux2.spi.rate_hz 12000000 +aux2.spi.filter_us 64 +aux2.spi.bct 0 +aux2.uart.mode 0 +aux2.uart.baud_rate 115200 +aux2.uart.poll_rate_us 100 +aux2.uart.rs422 0 +aux2.uart.cui_amt21_address 84 +aux2.quadrature.enabled 0 +aux2.quadrature.cpr 16384 +aux2.hall.enabled 0 +aux2.hall.polarity 0 +aux2.index.enabled 0 +aux2.sine_cosine.enabled 0 +aux2.sine_cosine.common 1700 +aux2.i2c_startup_delay_ms 30 +aux2.pins.0.mode 0 +aux2.pins.0.pull 0 +aux2.pins.1.mode 0 +aux2.pins.1.pull 0 +aux2.pins.2.mode 0 +aux2.pins.2.pull 0 +aux2.pins.3.mode 0 +aux2.pins.3.pull 0 +aux2.pins.4.mode 0 +aux2.pins.4.pull 0 +motor_position.sources.0.aux_number 1 +motor_position.sources.0.type 4 +motor_position.sources.0.i2c_device 0 +motor_position.sources.0.incremental_index -1 +motor_position.sources.0.cpr 84 +motor_position.sources.0.offset -5.000000 +motor_position.sources.0.sign 1 +motor_position.sources.0.debug_override -1 +motor_position.sources.0.reference 0 +motor_position.sources.0.pll_filter_hz 60.370068 +motor_position.sources.0.compensation_table.0 0.000000 +motor_position.sources.0.compensation_table.1 0.000000 +motor_position.sources.0.compensation_table.2 0.000000 +motor_position.sources.0.compensation_table.3 0.000000 +motor_position.sources.0.compensation_table.4 0.000000 +motor_position.sources.0.compensation_table.5 0.000000 +motor_position.sources.0.compensation_table.6 0.000000 +motor_position.sources.0.compensation_table.7 0.000000 +motor_position.sources.0.compensation_table.8 0.000000 +motor_position.sources.0.compensation_table.9 0.000000 +motor_position.sources.0.compensation_table.10 0.000000 +motor_position.sources.0.compensation_table.11 0.000000 +motor_position.sources.0.compensation_table.12 0.000000 +motor_position.sources.0.compensation_table.13 0.000000 +motor_position.sources.0.compensation_table.14 0.000000 +motor_position.sources.0.compensation_table.15 0.000000 +motor_position.sources.0.compensation_table.16 0.000000 +motor_position.sources.0.compensation_table.17 0.000000 +motor_position.sources.0.compensation_table.18 0.000000 +motor_position.sources.0.compensation_table.19 0.000000 +motor_position.sources.0.compensation_table.20 0.000000 +motor_position.sources.0.compensation_table.21 0.000000 +motor_position.sources.0.compensation_table.22 0.000000 +motor_position.sources.0.compensation_table.23 0.000000 +motor_position.sources.0.compensation_table.24 0.000000 +motor_position.sources.0.compensation_table.25 0.000000 +motor_position.sources.0.compensation_table.26 0.000000 +motor_position.sources.0.compensation_table.27 0.000000 +motor_position.sources.0.compensation_table.28 0.000000 +motor_position.sources.0.compensation_table.29 0.000000 +motor_position.sources.0.compensation_table.30 0.000000 +motor_position.sources.0.compensation_table.31 0.000000 +motor_position.sources.1.aux_number 1 +motor_position.sources.1.type 0 +motor_position.sources.1.i2c_device 0 +motor_position.sources.1.incremental_index -1 +motor_position.sources.1.cpr 16384 +motor_position.sources.1.offset 0.000000 +motor_position.sources.1.sign 1 +motor_position.sources.1.debug_override -1 +motor_position.sources.1.reference 0 +motor_position.sources.1.pll_filter_hz 10.000000 +motor_position.sources.1.compensation_table.0 0.000000 +motor_position.sources.1.compensation_table.1 0.000000 +motor_position.sources.1.compensation_table.2 0.000000 +motor_position.sources.1.compensation_table.3 0.000000 +motor_position.sources.1.compensation_table.4 0.000000 +motor_position.sources.1.compensation_table.5 0.000000 +motor_position.sources.1.compensation_table.6 0.000000 +motor_position.sources.1.compensation_table.7 0.000000 +motor_position.sources.1.compensation_table.8 0.000000 +motor_position.sources.1.compensation_table.9 0.000000 +motor_position.sources.1.compensation_table.10 0.000000 +motor_position.sources.1.compensation_table.11 0.000000 +motor_position.sources.1.compensation_table.12 0.000000 +motor_position.sources.1.compensation_table.13 0.000000 +motor_position.sources.1.compensation_table.14 0.000000 +motor_position.sources.1.compensation_table.15 0.000000 +motor_position.sources.1.compensation_table.16 0.000000 +motor_position.sources.1.compensation_table.17 0.000000 +motor_position.sources.1.compensation_table.18 0.000000 +motor_position.sources.1.compensation_table.19 0.000000 +motor_position.sources.1.compensation_table.20 0.000000 +motor_position.sources.1.compensation_table.21 0.000000 +motor_position.sources.1.compensation_table.22 0.000000 +motor_position.sources.1.compensation_table.23 0.000000 +motor_position.sources.1.compensation_table.24 0.000000 +motor_position.sources.1.compensation_table.25 0.000000 +motor_position.sources.1.compensation_table.26 0.000000 +motor_position.sources.1.compensation_table.27 0.000000 +motor_position.sources.1.compensation_table.28 0.000000 +motor_position.sources.1.compensation_table.29 0.000000 +motor_position.sources.1.compensation_table.30 0.000000 +motor_position.sources.1.compensation_table.31 0.000000 +motor_position.sources.2.aux_number 1 +motor_position.sources.2.type 0 +motor_position.sources.2.i2c_device 0 +motor_position.sources.2.incremental_index -1 +motor_position.sources.2.cpr 16384 +motor_position.sources.2.offset 0.000000 +motor_position.sources.2.sign 1 +motor_position.sources.2.debug_override -1 +motor_position.sources.2.reference 0 +motor_position.sources.2.pll_filter_hz 400.000000 +motor_position.sources.2.compensation_table.0 0.000000 +motor_position.sources.2.compensation_table.1 0.000000 +motor_position.sources.2.compensation_table.2 0.000000 +motor_position.sources.2.compensation_table.3 0.000000 +motor_position.sources.2.compensation_table.4 0.000000 +motor_position.sources.2.compensation_table.5 0.000000 +motor_position.sources.2.compensation_table.6 0.000000 +motor_position.sources.2.compensation_table.7 0.000000 +motor_position.sources.2.compensation_table.8 0.000000 +motor_position.sources.2.compensation_table.9 0.000000 +motor_position.sources.2.compensation_table.10 0.000000 +motor_position.sources.2.compensation_table.11 0.000000 +motor_position.sources.2.compensation_table.12 0.000000 +motor_position.sources.2.compensation_table.13 0.000000 +motor_position.sources.2.compensation_table.14 0.000000 +motor_position.sources.2.compensation_table.15 0.000000 +motor_position.sources.2.compensation_table.16 0.000000 +motor_position.sources.2.compensation_table.17 0.000000 +motor_position.sources.2.compensation_table.18 0.000000 +motor_position.sources.2.compensation_table.19 0.000000 +motor_position.sources.2.compensation_table.20 0.000000 +motor_position.sources.2.compensation_table.21 0.000000 +motor_position.sources.2.compensation_table.22 0.000000 +motor_position.sources.2.compensation_table.23 0.000000 +motor_position.sources.2.compensation_table.24 0.000000 +motor_position.sources.2.compensation_table.25 0.000000 +motor_position.sources.2.compensation_table.26 0.000000 +motor_position.sources.2.compensation_table.27 0.000000 +motor_position.sources.2.compensation_table.28 0.000000 +motor_position.sources.2.compensation_table.29 0.000000 +motor_position.sources.2.compensation_table.30 0.000000 +motor_position.sources.2.compensation_table.31 0.000000 +motor_position.commutation_source 0 +motor_position.output.source 0 +motor_position.output.offset 0.000000 +motor_position.output.sign 1 +motor_position.output.reference_source -1 +motor_position.rotor_to_output_ratio 1.000000 +motor.poles 28 +motor.phase_invert 0 +motor.resistance_ohm 0.217140 +motor.v_per_hz 0.436649 +motor.offset.0 0.000000 +motor.offset.1 0.000000 +motor.offset.2 0.000000 +motor.offset.3 0.000000 +motor.offset.4 0.000000 +motor.offset.5 0.000000 +motor.offset.6 0.000000 +motor.offset.7 0.000000 +motor.offset.8 0.000000 +motor.offset.9 0.000000 +motor.offset.10 0.000000 +motor.offset.11 0.000000 +motor.offset.12 0.000000 +motor.offset.13 0.000000 +motor.offset.14 0.000000 +motor.offset.15 0.000000 +motor.offset.16 0.000000 +motor.offset.17 0.000000 +motor.offset.18 0.000000 +motor.offset.19 0.000000 +motor.offset.20 0.000000 +motor.offset.21 0.000000 +motor.offset.22 0.000000 +motor.offset.23 0.000000 +motor.offset.24 0.000000 +motor.offset.25 0.000000 +motor.offset.26 0.000000 +motor.offset.27 0.000000 +motor.offset.28 0.000000 +motor.offset.29 0.000000 +motor.offset.30 0.000000 +motor.offset.31 0.000000 +motor.offset.32 0.000000 +motor.offset.33 0.000000 +motor.offset.34 0.000000 +motor.offset.35 0.000000 +motor.offset.36 0.000000 +motor.offset.37 0.000000 +motor.offset.38 0.000000 +motor.offset.39 0.000000 +motor.offset.40 0.000000 +motor.offset.41 0.000000 +motor.offset.42 0.000000 +motor.offset.43 0.000000 +motor.offset.44 0.000000 +motor.offset.45 0.000000 +motor.offset.46 0.000000 +motor.offset.47 0.000000 +motor.offset.48 0.000000 +motor.offset.49 0.000000 +motor.offset.50 0.000000 +motor.offset.51 0.000000 +motor.offset.52 0.000000 +motor.offset.53 0.000000 +motor.offset.54 0.000000 +motor.offset.55 0.000000 +motor.offset.56 0.000000 +motor.offset.57 0.000000 +motor.offset.58 0.000000 +motor.offset.59 0.000000 +motor.offset.60 0.000000 +motor.offset.61 0.000000 +motor.offset.62 0.000000 +motor.offset.63 0.000000 +motor.rotation_current_cutoff_A 10000.000000 +motor.rotation_current_scale 0.050000 +motor.rotation_torque_scale 14.700000 +motor.cogging_dq_scale 0.000000 +motor.cogging_dq_comp.0 0 +motor.cogging_dq_comp.1 0 +motor.cogging_dq_comp.2 0 +motor.cogging_dq_comp.3 0 +motor.cogging_dq_comp.4 0 +motor.cogging_dq_comp.5 0 +motor.cogging_dq_comp.6 0 +motor.cogging_dq_comp.7 0 +motor.cogging_dq_comp.8 0 +motor.cogging_dq_comp.9 0 +motor.cogging_dq_comp.10 0 +motor.cogging_dq_comp.11 0 +motor.cogging_dq_comp.12 0 +motor.cogging_dq_comp.13 0 +motor.cogging_dq_comp.14 0 +motor.cogging_dq_comp.15 0 +motor.cogging_dq_comp.16 0 +motor.cogging_dq_comp.17 0 +motor.cogging_dq_comp.18 0 +motor.cogging_dq_comp.19 0 +motor.cogging_dq_comp.20 0 +motor.cogging_dq_comp.21 0 +motor.cogging_dq_comp.22 0 +motor.cogging_dq_comp.23 0 +motor.cogging_dq_comp.24 0 +motor.cogging_dq_comp.25 0 +motor.cogging_dq_comp.26 0 +motor.cogging_dq_comp.27 0 +motor.cogging_dq_comp.28 0 +motor.cogging_dq_comp.29 0 +motor.cogging_dq_comp.30 0 +motor.cogging_dq_comp.31 0 +motor.cogging_dq_comp.32 0 +motor.cogging_dq_comp.33 0 +motor.cogging_dq_comp.34 0 +motor.cogging_dq_comp.35 0 +motor.cogging_dq_comp.36 0 +motor.cogging_dq_comp.37 0 +motor.cogging_dq_comp.38 0 +motor.cogging_dq_comp.39 0 +motor.cogging_dq_comp.40 0 +motor.cogging_dq_comp.41 0 +motor.cogging_dq_comp.42 0 +motor.cogging_dq_comp.43 0 +motor.cogging_dq_comp.44 0 +motor.cogging_dq_comp.45 0 +motor.cogging_dq_comp.46 0 +motor.cogging_dq_comp.47 0 +motor.cogging_dq_comp.48 0 +motor.cogging_dq_comp.49 0 +motor.cogging_dq_comp.50 0 +motor.cogging_dq_comp.51 0 +motor.cogging_dq_comp.52 0 +motor.cogging_dq_comp.53 0 +motor.cogging_dq_comp.54 0 +motor.cogging_dq_comp.55 0 +motor.cogging_dq_comp.56 0 +motor.cogging_dq_comp.57 0 +motor.cogging_dq_comp.58 0 +motor.cogging_dq_comp.59 0 +motor.cogging_dq_comp.60 0 +motor.cogging_dq_comp.61 0 +motor.cogging_dq_comp.62 0 +motor.cogging_dq_comp.63 0 +motor.cogging_dq_comp.64 0 +motor.cogging_dq_comp.65 0 +motor.cogging_dq_comp.66 0 +motor.cogging_dq_comp.67 0 +motor.cogging_dq_comp.68 0 +motor.cogging_dq_comp.69 0 +motor.cogging_dq_comp.70 0 +motor.cogging_dq_comp.71 0 +motor.cogging_dq_comp.72 0 +motor.cogging_dq_comp.73 0 +motor.cogging_dq_comp.74 0 +motor.cogging_dq_comp.75 0 +motor.cogging_dq_comp.76 0 +motor.cogging_dq_comp.77 0 +motor.cogging_dq_comp.78 0 +motor.cogging_dq_comp.79 0 +motor.cogging_dq_comp.80 0 +motor.cogging_dq_comp.81 0 +motor.cogging_dq_comp.82 0 +motor.cogging_dq_comp.83 0 +motor.cogging_dq_comp.84 0 +motor.cogging_dq_comp.85 0 +motor.cogging_dq_comp.86 0 +motor.cogging_dq_comp.87 0 +motor.cogging_dq_comp.88 0 +motor.cogging_dq_comp.89 0 +motor.cogging_dq_comp.90 0 +motor.cogging_dq_comp.91 0 +motor.cogging_dq_comp.92 0 +motor.cogging_dq_comp.93 0 +motor.cogging_dq_comp.94 0 +motor.cogging_dq_comp.95 0 +motor.cogging_dq_comp.96 0 +motor.cogging_dq_comp.97 0 +motor.cogging_dq_comp.98 0 +motor.cogging_dq_comp.99 0 +motor.cogging_dq_comp.100 0 +motor.cogging_dq_comp.101 0 +motor.cogging_dq_comp.102 0 +motor.cogging_dq_comp.103 0 +motor.cogging_dq_comp.104 0 +motor.cogging_dq_comp.105 0 +motor.cogging_dq_comp.106 0 +motor.cogging_dq_comp.107 0 +motor.cogging_dq_comp.108 0 +motor.cogging_dq_comp.109 0 +motor.cogging_dq_comp.110 0 +motor.cogging_dq_comp.111 0 +motor.cogging_dq_comp.112 0 +motor.cogging_dq_comp.113 0 +motor.cogging_dq_comp.114 0 +motor.cogging_dq_comp.115 0 +motor.cogging_dq_comp.116 0 +motor.cogging_dq_comp.117 0 +motor.cogging_dq_comp.118 0 +motor.cogging_dq_comp.119 0 +motor.cogging_dq_comp.120 0 +motor.cogging_dq_comp.121 0 +motor.cogging_dq_comp.122 0 +motor.cogging_dq_comp.123 0 +motor.cogging_dq_comp.124 0 +motor.cogging_dq_comp.125 0 +motor.cogging_dq_comp.126 0 +motor.cogging_dq_comp.127 0 +motor.cogging_dq_comp.128 0 +motor.cogging_dq_comp.129 0 +motor.cogging_dq_comp.130 0 +motor.cogging_dq_comp.131 0 +motor.cogging_dq_comp.132 0 +motor.cogging_dq_comp.133 0 +motor.cogging_dq_comp.134 0 +motor.cogging_dq_comp.135 0 +motor.cogging_dq_comp.136 0 +motor.cogging_dq_comp.137 0 +motor.cogging_dq_comp.138 0 +motor.cogging_dq_comp.139 0 +motor.cogging_dq_comp.140 0 +motor.cogging_dq_comp.141 0 +motor.cogging_dq_comp.142 0 +motor.cogging_dq_comp.143 0 +motor.cogging_dq_comp.144 0 +motor.cogging_dq_comp.145 0 +motor.cogging_dq_comp.146 0 +motor.cogging_dq_comp.147 0 +motor.cogging_dq_comp.148 0 +motor.cogging_dq_comp.149 0 +motor.cogging_dq_comp.150 0 +motor.cogging_dq_comp.151 0 +motor.cogging_dq_comp.152 0 +motor.cogging_dq_comp.153 0 +motor.cogging_dq_comp.154 0 +motor.cogging_dq_comp.155 0 +motor.cogging_dq_comp.156 0 +motor.cogging_dq_comp.157 0 +motor.cogging_dq_comp.158 0 +motor.cogging_dq_comp.159 0 +motor.cogging_dq_comp.160 0 +motor.cogging_dq_comp.161 0 +motor.cogging_dq_comp.162 0 +motor.cogging_dq_comp.163 0 +motor.cogging_dq_comp.164 0 +motor.cogging_dq_comp.165 0 +motor.cogging_dq_comp.166 0 +motor.cogging_dq_comp.167 0 +motor.cogging_dq_comp.168 0 +motor.cogging_dq_comp.169 0 +motor.cogging_dq_comp.170 0 +motor.cogging_dq_comp.171 0 +motor.cogging_dq_comp.172 0 +motor.cogging_dq_comp.173 0 +motor.cogging_dq_comp.174 0 +motor.cogging_dq_comp.175 0 +motor.cogging_dq_comp.176 0 +motor.cogging_dq_comp.177 0 +motor.cogging_dq_comp.178 0 +motor.cogging_dq_comp.179 0 +motor.cogging_dq_comp.180 0 +motor.cogging_dq_comp.181 0 +motor.cogging_dq_comp.182 0 +motor.cogging_dq_comp.183 0 +motor.cogging_dq_comp.184 0 +motor.cogging_dq_comp.185 0 +motor.cogging_dq_comp.186 0 +motor.cogging_dq_comp.187 0 +motor.cogging_dq_comp.188 0 +motor.cogging_dq_comp.189 0 +motor.cogging_dq_comp.190 0 +motor.cogging_dq_comp.191 0 +motor.cogging_dq_comp.192 0 +motor.cogging_dq_comp.193 0 +motor.cogging_dq_comp.194 0 +motor.cogging_dq_comp.195 0 +motor.cogging_dq_comp.196 0 +motor.cogging_dq_comp.197 0 +motor.cogging_dq_comp.198 0 +motor.cogging_dq_comp.199 0 +motor.cogging_dq_comp.200 0 +motor.cogging_dq_comp.201 0 +motor.cogging_dq_comp.202 0 +motor.cogging_dq_comp.203 0 +motor.cogging_dq_comp.204 0 +motor.cogging_dq_comp.205 0 +motor.cogging_dq_comp.206 0 +motor.cogging_dq_comp.207 0 +motor.cogging_dq_comp.208 0 +motor.cogging_dq_comp.209 0 +motor.cogging_dq_comp.210 0 +motor.cogging_dq_comp.211 0 +motor.cogging_dq_comp.212 0 +motor.cogging_dq_comp.213 0 +motor.cogging_dq_comp.214 0 +motor.cogging_dq_comp.215 0 +motor.cogging_dq_comp.216 0 +motor.cogging_dq_comp.217 0 +motor.cogging_dq_comp.218 0 +motor.cogging_dq_comp.219 0 +motor.cogging_dq_comp.220 0 +motor.cogging_dq_comp.221 0 +motor.cogging_dq_comp.222 0 +motor.cogging_dq_comp.223 0 +motor.cogging_dq_comp.224 0 +motor.cogging_dq_comp.225 0 +motor.cogging_dq_comp.226 0 +motor.cogging_dq_comp.227 0 +motor.cogging_dq_comp.228 0 +motor.cogging_dq_comp.229 0 +motor.cogging_dq_comp.230 0 +motor.cogging_dq_comp.231 0 +motor.cogging_dq_comp.232 0 +motor.cogging_dq_comp.233 0 +motor.cogging_dq_comp.234 0 +motor.cogging_dq_comp.235 0 +motor.cogging_dq_comp.236 0 +motor.cogging_dq_comp.237 0 +motor.cogging_dq_comp.238 0 +motor.cogging_dq_comp.239 0 +motor.cogging_dq_comp.240 0 +motor.cogging_dq_comp.241 0 +motor.cogging_dq_comp.242 0 +motor.cogging_dq_comp.243 0 +motor.cogging_dq_comp.244 0 +motor.cogging_dq_comp.245 0 +motor.cogging_dq_comp.246 0 +motor.cogging_dq_comp.247 0 +motor.cogging_dq_comp.248 0 +motor.cogging_dq_comp.249 0 +motor.cogging_dq_comp.250 0 +motor.cogging_dq_comp.251 0 +motor.cogging_dq_comp.252 0 +motor.cogging_dq_comp.253 0 +motor.cogging_dq_comp.254 0 +motor.cogging_dq_comp.255 0 +motor.cogging_dq_comp.256 0 +motor.cogging_dq_comp.257 0 +motor.cogging_dq_comp.258 0 +motor.cogging_dq_comp.259 0 +motor.cogging_dq_comp.260 0 +motor.cogging_dq_comp.261 0 +motor.cogging_dq_comp.262 0 +motor.cogging_dq_comp.263 0 +motor.cogging_dq_comp.264 0 +motor.cogging_dq_comp.265 0 +motor.cogging_dq_comp.266 0 +motor.cogging_dq_comp.267 0 +motor.cogging_dq_comp.268 0 +motor.cogging_dq_comp.269 0 +motor.cogging_dq_comp.270 0 +motor.cogging_dq_comp.271 0 +motor.cogging_dq_comp.272 0 +motor.cogging_dq_comp.273 0 +motor.cogging_dq_comp.274 0 +motor.cogging_dq_comp.275 0 +motor.cogging_dq_comp.276 0 +motor.cogging_dq_comp.277 0 +motor.cogging_dq_comp.278 0 +motor.cogging_dq_comp.279 0 +motor.cogging_dq_comp.280 0 +motor.cogging_dq_comp.281 0 +motor.cogging_dq_comp.282 0 +motor.cogging_dq_comp.283 0 +motor.cogging_dq_comp.284 0 +motor.cogging_dq_comp.285 0 +motor.cogging_dq_comp.286 0 +motor.cogging_dq_comp.287 0 +motor.cogging_dq_comp.288 0 +motor.cogging_dq_comp.289 0 +motor.cogging_dq_comp.290 0 +motor.cogging_dq_comp.291 0 +motor.cogging_dq_comp.292 0 +motor.cogging_dq_comp.293 0 +motor.cogging_dq_comp.294 0 +motor.cogging_dq_comp.295 0 +motor.cogging_dq_comp.296 0 +motor.cogging_dq_comp.297 0 +motor.cogging_dq_comp.298 0 +motor.cogging_dq_comp.299 0 +motor.cogging_dq_comp.300 0 +motor.cogging_dq_comp.301 0 +motor.cogging_dq_comp.302 0 +motor.cogging_dq_comp.303 0 +motor.cogging_dq_comp.304 0 +motor.cogging_dq_comp.305 0 +motor.cogging_dq_comp.306 0 +motor.cogging_dq_comp.307 0 +motor.cogging_dq_comp.308 0 +motor.cogging_dq_comp.309 0 +motor.cogging_dq_comp.310 0 +motor.cogging_dq_comp.311 0 +motor.cogging_dq_comp.312 0 +motor.cogging_dq_comp.313 0 +motor.cogging_dq_comp.314 0 +motor.cogging_dq_comp.315 0 +motor.cogging_dq_comp.316 0 +motor.cogging_dq_comp.317 0 +motor.cogging_dq_comp.318 0 +motor.cogging_dq_comp.319 0 +motor.cogging_dq_comp.320 0 +motor.cogging_dq_comp.321 0 +motor.cogging_dq_comp.322 0 +motor.cogging_dq_comp.323 0 +motor.cogging_dq_comp.324 0 +motor.cogging_dq_comp.325 0 +motor.cogging_dq_comp.326 0 +motor.cogging_dq_comp.327 0 +motor.cogging_dq_comp.328 0 +motor.cogging_dq_comp.329 0 +motor.cogging_dq_comp.330 0 +motor.cogging_dq_comp.331 0 +motor.cogging_dq_comp.332 0 +motor.cogging_dq_comp.333 0 +motor.cogging_dq_comp.334 0 +motor.cogging_dq_comp.335 0 +motor.cogging_dq_comp.336 0 +motor.cogging_dq_comp.337 0 +motor.cogging_dq_comp.338 0 +motor.cogging_dq_comp.339 0 +motor.cogging_dq_comp.340 0 +motor.cogging_dq_comp.341 0 +motor.cogging_dq_comp.342 0 +motor.cogging_dq_comp.343 0 +motor.cogging_dq_comp.344 0 +motor.cogging_dq_comp.345 0 +motor.cogging_dq_comp.346 0 +motor.cogging_dq_comp.347 0 +motor.cogging_dq_comp.348 0 +motor.cogging_dq_comp.349 0 +motor.cogging_dq_comp.350 0 +motor.cogging_dq_comp.351 0 +motor.cogging_dq_comp.352 0 +motor.cogging_dq_comp.353 0 +motor.cogging_dq_comp.354 0 +motor.cogging_dq_comp.355 0 +motor.cogging_dq_comp.356 0 +motor.cogging_dq_comp.357 0 +motor.cogging_dq_comp.358 0 +motor.cogging_dq_comp.359 0 +motor.cogging_dq_comp.360 0 +motor.cogging_dq_comp.361 0 +motor.cogging_dq_comp.362 0 +motor.cogging_dq_comp.363 0 +motor.cogging_dq_comp.364 0 +motor.cogging_dq_comp.365 0 +motor.cogging_dq_comp.366 0 +motor.cogging_dq_comp.367 0 +motor.cogging_dq_comp.368 0 +motor.cogging_dq_comp.369 0 +motor.cogging_dq_comp.370 0 +motor.cogging_dq_comp.371 0 +motor.cogging_dq_comp.372 0 +motor.cogging_dq_comp.373 0 +motor.cogging_dq_comp.374 0 +motor.cogging_dq_comp.375 0 +motor.cogging_dq_comp.376 0 +motor.cogging_dq_comp.377 0 +motor.cogging_dq_comp.378 0 +motor.cogging_dq_comp.379 0 +motor.cogging_dq_comp.380 0 +motor.cogging_dq_comp.381 0 +motor.cogging_dq_comp.382 0 +motor.cogging_dq_comp.383 0 +motor.cogging_dq_comp.384 0 +motor.cogging_dq_comp.385 0 +motor.cogging_dq_comp.386 0 +motor.cogging_dq_comp.387 0 +motor.cogging_dq_comp.388 0 +motor.cogging_dq_comp.389 0 +motor.cogging_dq_comp.390 0 +motor.cogging_dq_comp.391 0 +motor.cogging_dq_comp.392 0 +motor.cogging_dq_comp.393 0 +motor.cogging_dq_comp.394 0 +motor.cogging_dq_comp.395 0 +motor.cogging_dq_comp.396 0 +motor.cogging_dq_comp.397 0 +motor.cogging_dq_comp.398 0 +motor.cogging_dq_comp.399 0 +motor.cogging_dq_comp.400 0 +motor.cogging_dq_comp.401 0 +motor.cogging_dq_comp.402 0 +motor.cogging_dq_comp.403 0 +motor.cogging_dq_comp.404 0 +motor.cogging_dq_comp.405 0 +motor.cogging_dq_comp.406 0 +motor.cogging_dq_comp.407 0 +motor.cogging_dq_comp.408 0 +motor.cogging_dq_comp.409 0 +motor.cogging_dq_comp.410 0 +motor.cogging_dq_comp.411 0 +motor.cogging_dq_comp.412 0 +motor.cogging_dq_comp.413 0 +motor.cogging_dq_comp.414 0 +motor.cogging_dq_comp.415 0 +motor.cogging_dq_comp.416 0 +motor.cogging_dq_comp.417 0 +motor.cogging_dq_comp.418 0 +motor.cogging_dq_comp.419 0 +motor.cogging_dq_comp.420 0 +motor.cogging_dq_comp.421 0 +motor.cogging_dq_comp.422 0 +motor.cogging_dq_comp.423 0 +motor.cogging_dq_comp.424 0 +motor.cogging_dq_comp.425 0 +motor.cogging_dq_comp.426 0 +motor.cogging_dq_comp.427 0 +motor.cogging_dq_comp.428 0 +motor.cogging_dq_comp.429 0 +motor.cogging_dq_comp.430 0 +motor.cogging_dq_comp.431 0 +motor.cogging_dq_comp.432 0 +motor.cogging_dq_comp.433 0 +motor.cogging_dq_comp.434 0 +motor.cogging_dq_comp.435 0 +motor.cogging_dq_comp.436 0 +motor.cogging_dq_comp.437 0 +motor.cogging_dq_comp.438 0 +motor.cogging_dq_comp.439 0 +motor.cogging_dq_comp.440 0 +motor.cogging_dq_comp.441 0 +motor.cogging_dq_comp.442 0 +motor.cogging_dq_comp.443 0 +motor.cogging_dq_comp.444 0 +motor.cogging_dq_comp.445 0 +motor.cogging_dq_comp.446 0 +motor.cogging_dq_comp.447 0 +motor.cogging_dq_comp.448 0 +motor.cogging_dq_comp.449 0 +motor.cogging_dq_comp.450 0 +motor.cogging_dq_comp.451 0 +motor.cogging_dq_comp.452 0 +motor.cogging_dq_comp.453 0 +motor.cogging_dq_comp.454 0 +motor.cogging_dq_comp.455 0 +motor.cogging_dq_comp.456 0 +motor.cogging_dq_comp.457 0 +motor.cogging_dq_comp.458 0 +motor.cogging_dq_comp.459 0 +motor.cogging_dq_comp.460 0 +motor.cogging_dq_comp.461 0 +motor.cogging_dq_comp.462 0 +motor.cogging_dq_comp.463 0 +motor.cogging_dq_comp.464 0 +motor.cogging_dq_comp.465 0 +motor.cogging_dq_comp.466 0 +motor.cogging_dq_comp.467 0 +motor.cogging_dq_comp.468 0 +motor.cogging_dq_comp.469 0 +motor.cogging_dq_comp.470 0 +motor.cogging_dq_comp.471 0 +motor.cogging_dq_comp.472 0 +motor.cogging_dq_comp.473 0 +motor.cogging_dq_comp.474 0 +motor.cogging_dq_comp.475 0 +motor.cogging_dq_comp.476 0 +motor.cogging_dq_comp.477 0 +motor.cogging_dq_comp.478 0 +motor.cogging_dq_comp.479 0 +motor.cogging_dq_comp.480 0 +motor.cogging_dq_comp.481 0 +motor.cogging_dq_comp.482 0 +motor.cogging_dq_comp.483 0 +motor.cogging_dq_comp.484 0 +motor.cogging_dq_comp.485 0 +motor.cogging_dq_comp.486 0 +motor.cogging_dq_comp.487 0 +motor.cogging_dq_comp.488 0 +motor.cogging_dq_comp.489 0 +motor.cogging_dq_comp.490 0 +motor.cogging_dq_comp.491 0 +motor.cogging_dq_comp.492 0 +motor.cogging_dq_comp.493 0 +motor.cogging_dq_comp.494 0 +motor.cogging_dq_comp.495 0 +motor.cogging_dq_comp.496 0 +motor.cogging_dq_comp.497 0 +motor.cogging_dq_comp.498 0 +motor.cogging_dq_comp.499 0 +motor.cogging_dq_comp.500 0 +motor.cogging_dq_comp.501 0 +motor.cogging_dq_comp.502 0 +motor.cogging_dq_comp.503 0 +motor.cogging_dq_comp.504 0 +motor.cogging_dq_comp.505 0 +motor.cogging_dq_comp.506 0 +motor.cogging_dq_comp.507 0 +motor.cogging_dq_comp.508 0 +motor.cogging_dq_comp.509 0 +motor.cogging_dq_comp.510 0 +motor.cogging_dq_comp.511 0 +motor.cogging_dq_comp.512 0 +motor.cogging_dq_comp.513 0 +motor.cogging_dq_comp.514 0 +motor.cogging_dq_comp.515 0 +motor.cogging_dq_comp.516 0 +motor.cogging_dq_comp.517 0 +motor.cogging_dq_comp.518 0 +motor.cogging_dq_comp.519 0 +motor.cogging_dq_comp.520 0 +motor.cogging_dq_comp.521 0 +motor.cogging_dq_comp.522 0 +motor.cogging_dq_comp.523 0 +motor.cogging_dq_comp.524 0 +motor.cogging_dq_comp.525 0 +motor.cogging_dq_comp.526 0 +motor.cogging_dq_comp.527 0 +motor.cogging_dq_comp.528 0 +motor.cogging_dq_comp.529 0 +motor.cogging_dq_comp.530 0 +motor.cogging_dq_comp.531 0 +motor.cogging_dq_comp.532 0 +motor.cogging_dq_comp.533 0 +motor.cogging_dq_comp.534 0 +motor.cogging_dq_comp.535 0 +motor.cogging_dq_comp.536 0 +motor.cogging_dq_comp.537 0 +motor.cogging_dq_comp.538 0 +motor.cogging_dq_comp.539 0 +motor.cogging_dq_comp.540 0 +motor.cogging_dq_comp.541 0 +motor.cogging_dq_comp.542 0 +motor.cogging_dq_comp.543 0 +motor.cogging_dq_comp.544 0 +motor.cogging_dq_comp.545 0 +motor.cogging_dq_comp.546 0 +motor.cogging_dq_comp.547 0 +motor.cogging_dq_comp.548 0 +motor.cogging_dq_comp.549 0 +motor.cogging_dq_comp.550 0 +motor.cogging_dq_comp.551 0 +motor.cogging_dq_comp.552 0 +motor.cogging_dq_comp.553 0 +motor.cogging_dq_comp.554 0 +motor.cogging_dq_comp.555 0 +motor.cogging_dq_comp.556 0 +motor.cogging_dq_comp.557 0 +motor.cogging_dq_comp.558 0 +motor.cogging_dq_comp.559 0 +motor.cogging_dq_comp.560 0 +motor.cogging_dq_comp.561 0 +motor.cogging_dq_comp.562 0 +motor.cogging_dq_comp.563 0 +motor.cogging_dq_comp.564 0 +motor.cogging_dq_comp.565 0 +motor.cogging_dq_comp.566 0 +motor.cogging_dq_comp.567 0 +motor.cogging_dq_comp.568 0 +motor.cogging_dq_comp.569 0 +motor.cogging_dq_comp.570 0 +motor.cogging_dq_comp.571 0 +motor.cogging_dq_comp.572 0 +motor.cogging_dq_comp.573 0 +motor.cogging_dq_comp.574 0 +motor.cogging_dq_comp.575 0 +motor.cogging_dq_comp.576 0 +motor.cogging_dq_comp.577 0 +motor.cogging_dq_comp.578 0 +motor.cogging_dq_comp.579 0 +motor.cogging_dq_comp.580 0 +motor.cogging_dq_comp.581 0 +motor.cogging_dq_comp.582 0 +motor.cogging_dq_comp.583 0 +motor.cogging_dq_comp.584 0 +motor.cogging_dq_comp.585 0 +motor.cogging_dq_comp.586 0 +motor.cogging_dq_comp.587 0 +motor.cogging_dq_comp.588 0 +motor.cogging_dq_comp.589 0 +motor.cogging_dq_comp.590 0 +motor.cogging_dq_comp.591 0 +motor.cogging_dq_comp.592 0 +motor.cogging_dq_comp.593 0 +motor.cogging_dq_comp.594 0 +motor.cogging_dq_comp.595 0 +motor.cogging_dq_comp.596 0 +motor.cogging_dq_comp.597 0 +motor.cogging_dq_comp.598 0 +motor.cogging_dq_comp.599 0 +motor.cogging_dq_comp.600 0 +motor.cogging_dq_comp.601 0 +motor.cogging_dq_comp.602 0 +motor.cogging_dq_comp.603 0 +motor.cogging_dq_comp.604 0 +motor.cogging_dq_comp.605 0 +motor.cogging_dq_comp.606 0 +motor.cogging_dq_comp.607 0 +motor.cogging_dq_comp.608 0 +motor.cogging_dq_comp.609 0 +motor.cogging_dq_comp.610 0 +motor.cogging_dq_comp.611 0 +motor.cogging_dq_comp.612 0 +motor.cogging_dq_comp.613 0 +motor.cogging_dq_comp.614 0 +motor.cogging_dq_comp.615 0 +motor.cogging_dq_comp.616 0 +motor.cogging_dq_comp.617 0 +motor.cogging_dq_comp.618 0 +motor.cogging_dq_comp.619 0 +motor.cogging_dq_comp.620 0 +motor.cogging_dq_comp.621 0 +motor.cogging_dq_comp.622 0 +motor.cogging_dq_comp.623 0 +motor.cogging_dq_comp.624 0 +motor.cogging_dq_comp.625 0 +motor.cogging_dq_comp.626 0 +motor.cogging_dq_comp.627 0 +motor.cogging_dq_comp.628 0 +motor.cogging_dq_comp.629 0 +motor.cogging_dq_comp.630 0 +motor.cogging_dq_comp.631 0 +motor.cogging_dq_comp.632 0 +motor.cogging_dq_comp.633 0 +motor.cogging_dq_comp.634 0 +motor.cogging_dq_comp.635 0 +motor.cogging_dq_comp.636 0 +motor.cogging_dq_comp.637 0 +motor.cogging_dq_comp.638 0 +motor.cogging_dq_comp.639 0 +motor.cogging_dq_comp.640 0 +motor.cogging_dq_comp.641 0 +motor.cogging_dq_comp.642 0 +motor.cogging_dq_comp.643 0 +motor.cogging_dq_comp.644 0 +motor.cogging_dq_comp.645 0 +motor.cogging_dq_comp.646 0 +motor.cogging_dq_comp.647 0 +motor.cogging_dq_comp.648 0 +motor.cogging_dq_comp.649 0 +motor.cogging_dq_comp.650 0 +motor.cogging_dq_comp.651 0 +motor.cogging_dq_comp.652 0 +motor.cogging_dq_comp.653 0 +motor.cogging_dq_comp.654 0 +motor.cogging_dq_comp.655 0 +motor.cogging_dq_comp.656 0 +motor.cogging_dq_comp.657 0 +motor.cogging_dq_comp.658 0 +motor.cogging_dq_comp.659 0 +motor.cogging_dq_comp.660 0 +motor.cogging_dq_comp.661 0 +motor.cogging_dq_comp.662 0 +motor.cogging_dq_comp.663 0 +motor.cogging_dq_comp.664 0 +motor.cogging_dq_comp.665 0 +motor.cogging_dq_comp.666 0 +motor.cogging_dq_comp.667 0 +motor.cogging_dq_comp.668 0 +motor.cogging_dq_comp.669 0 +motor.cogging_dq_comp.670 0 +motor.cogging_dq_comp.671 0 +motor.cogging_dq_comp.672 0 +motor.cogging_dq_comp.673 0 +motor.cogging_dq_comp.674 0 +motor.cogging_dq_comp.675 0 +motor.cogging_dq_comp.676 0 +motor.cogging_dq_comp.677 0 +motor.cogging_dq_comp.678 0 +motor.cogging_dq_comp.679 0 +motor.cogging_dq_comp.680 0 +motor.cogging_dq_comp.681 0 +motor.cogging_dq_comp.682 0 +motor.cogging_dq_comp.683 0 +motor.cogging_dq_comp.684 0 +motor.cogging_dq_comp.685 0 +motor.cogging_dq_comp.686 0 +motor.cogging_dq_comp.687 0 +motor.cogging_dq_comp.688 0 +motor.cogging_dq_comp.689 0 +motor.cogging_dq_comp.690 0 +motor.cogging_dq_comp.691 0 +motor.cogging_dq_comp.692 0 +motor.cogging_dq_comp.693 0 +motor.cogging_dq_comp.694 0 +motor.cogging_dq_comp.695 0 +motor.cogging_dq_comp.696 0 +motor.cogging_dq_comp.697 0 +motor.cogging_dq_comp.698 0 +motor.cogging_dq_comp.699 0 +motor.cogging_dq_comp.700 0 +motor.cogging_dq_comp.701 0 +motor.cogging_dq_comp.702 0 +motor.cogging_dq_comp.703 0 +motor.cogging_dq_comp.704 0 +motor.cogging_dq_comp.705 0 +motor.cogging_dq_comp.706 0 +motor.cogging_dq_comp.707 0 +motor.cogging_dq_comp.708 0 +motor.cogging_dq_comp.709 0 +motor.cogging_dq_comp.710 0 +motor.cogging_dq_comp.711 0 +motor.cogging_dq_comp.712 0 +motor.cogging_dq_comp.713 0 +motor.cogging_dq_comp.714 0 +motor.cogging_dq_comp.715 0 +motor.cogging_dq_comp.716 0 +motor.cogging_dq_comp.717 0 +motor.cogging_dq_comp.718 0 +motor.cogging_dq_comp.719 0 +motor.cogging_dq_comp.720 0 +motor.cogging_dq_comp.721 0 +motor.cogging_dq_comp.722 0 +motor.cogging_dq_comp.723 0 +motor.cogging_dq_comp.724 0 +motor.cogging_dq_comp.725 0 +motor.cogging_dq_comp.726 0 +motor.cogging_dq_comp.727 0 +motor.cogging_dq_comp.728 0 +motor.cogging_dq_comp.729 0 +motor.cogging_dq_comp.730 0 +motor.cogging_dq_comp.731 0 +motor.cogging_dq_comp.732 0 +motor.cogging_dq_comp.733 0 +motor.cogging_dq_comp.734 0 +motor.cogging_dq_comp.735 0 +motor.cogging_dq_comp.736 0 +motor.cogging_dq_comp.737 0 +motor.cogging_dq_comp.738 0 +motor.cogging_dq_comp.739 0 +motor.cogging_dq_comp.740 0 +motor.cogging_dq_comp.741 0 +motor.cogging_dq_comp.742 0 +motor.cogging_dq_comp.743 0 +motor.cogging_dq_comp.744 0 +motor.cogging_dq_comp.745 0 +motor.cogging_dq_comp.746 0 +motor.cogging_dq_comp.747 0 +motor.cogging_dq_comp.748 0 +motor.cogging_dq_comp.749 0 +motor.cogging_dq_comp.750 0 +motor.cogging_dq_comp.751 0 +motor.cogging_dq_comp.752 0 +motor.cogging_dq_comp.753 0 +motor.cogging_dq_comp.754 0 +motor.cogging_dq_comp.755 0 +motor.cogging_dq_comp.756 0 +motor.cogging_dq_comp.757 0 +motor.cogging_dq_comp.758 0 +motor.cogging_dq_comp.759 0 +motor.cogging_dq_comp.760 0 +motor.cogging_dq_comp.761 0 +motor.cogging_dq_comp.762 0 +motor.cogging_dq_comp.763 0 +motor.cogging_dq_comp.764 0 +motor.cogging_dq_comp.765 0 +motor.cogging_dq_comp.766 0 +motor.cogging_dq_comp.767 0 +motor.cogging_dq_comp.768 0 +motor.cogging_dq_comp.769 0 +motor.cogging_dq_comp.770 0 +motor.cogging_dq_comp.771 0 +motor.cogging_dq_comp.772 0 +motor.cogging_dq_comp.773 0 +motor.cogging_dq_comp.774 0 +motor.cogging_dq_comp.775 0 +motor.cogging_dq_comp.776 0 +motor.cogging_dq_comp.777 0 +motor.cogging_dq_comp.778 0 +motor.cogging_dq_comp.779 0 +motor.cogging_dq_comp.780 0 +motor.cogging_dq_comp.781 0 +motor.cogging_dq_comp.782 0 +motor.cogging_dq_comp.783 0 +motor.cogging_dq_comp.784 0 +motor.cogging_dq_comp.785 0 +motor.cogging_dq_comp.786 0 +motor.cogging_dq_comp.787 0 +motor.cogging_dq_comp.788 0 +motor.cogging_dq_comp.789 0 +motor.cogging_dq_comp.790 0 +motor.cogging_dq_comp.791 0 +motor.cogging_dq_comp.792 0 +motor.cogging_dq_comp.793 0 +motor.cogging_dq_comp.794 0 +motor.cogging_dq_comp.795 0 +motor.cogging_dq_comp.796 0 +motor.cogging_dq_comp.797 0 +motor.cogging_dq_comp.798 0 +motor.cogging_dq_comp.799 0 +motor.cogging_dq_comp.800 0 +motor.cogging_dq_comp.801 0 +motor.cogging_dq_comp.802 0 +motor.cogging_dq_comp.803 0 +motor.cogging_dq_comp.804 0 +motor.cogging_dq_comp.805 0 +motor.cogging_dq_comp.806 0 +motor.cogging_dq_comp.807 0 +motor.cogging_dq_comp.808 0 +motor.cogging_dq_comp.809 0 +motor.cogging_dq_comp.810 0 +motor.cogging_dq_comp.811 0 +motor.cogging_dq_comp.812 0 +motor.cogging_dq_comp.813 0 +motor.cogging_dq_comp.814 0 +motor.cogging_dq_comp.815 0 +motor.cogging_dq_comp.816 0 +motor.cogging_dq_comp.817 0 +motor.cogging_dq_comp.818 0 +motor.cogging_dq_comp.819 0 +motor.cogging_dq_comp.820 0 +motor.cogging_dq_comp.821 0 +motor.cogging_dq_comp.822 0 +motor.cogging_dq_comp.823 0 +motor.cogging_dq_comp.824 0 +motor.cogging_dq_comp.825 0 +motor.cogging_dq_comp.826 0 +motor.cogging_dq_comp.827 0 +motor.cogging_dq_comp.828 0 +motor.cogging_dq_comp.829 0 +motor.cogging_dq_comp.830 0 +motor.cogging_dq_comp.831 0 +motor.cogging_dq_comp.832 0 +motor.cogging_dq_comp.833 0 +motor.cogging_dq_comp.834 0 +motor.cogging_dq_comp.835 0 +motor.cogging_dq_comp.836 0 +motor.cogging_dq_comp.837 0 +motor.cogging_dq_comp.838 0 +motor.cogging_dq_comp.839 0 +motor.cogging_dq_comp.840 0 +motor.cogging_dq_comp.841 0 +motor.cogging_dq_comp.842 0 +motor.cogging_dq_comp.843 0 +motor.cogging_dq_comp.844 0 +motor.cogging_dq_comp.845 0 +motor.cogging_dq_comp.846 0 +motor.cogging_dq_comp.847 0 +motor.cogging_dq_comp.848 0 +motor.cogging_dq_comp.849 0 +motor.cogging_dq_comp.850 0 +motor.cogging_dq_comp.851 0 +motor.cogging_dq_comp.852 0 +motor.cogging_dq_comp.853 0 +motor.cogging_dq_comp.854 0 +motor.cogging_dq_comp.855 0 +motor.cogging_dq_comp.856 0 +motor.cogging_dq_comp.857 0 +motor.cogging_dq_comp.858 0 +motor.cogging_dq_comp.859 0 +motor.cogging_dq_comp.860 0 +motor.cogging_dq_comp.861 0 +motor.cogging_dq_comp.862 0 +motor.cogging_dq_comp.863 0 +motor.cogging_dq_comp.864 0 +motor.cogging_dq_comp.865 0 +motor.cogging_dq_comp.866 0 +motor.cogging_dq_comp.867 0 +motor.cogging_dq_comp.868 0 +motor.cogging_dq_comp.869 0 +motor.cogging_dq_comp.870 0 +motor.cogging_dq_comp.871 0 +motor.cogging_dq_comp.872 0 +motor.cogging_dq_comp.873 0 +motor.cogging_dq_comp.874 0 +motor.cogging_dq_comp.875 0 +motor.cogging_dq_comp.876 0 +motor.cogging_dq_comp.877 0 +motor.cogging_dq_comp.878 0 +motor.cogging_dq_comp.879 0 +motor.cogging_dq_comp.880 0 +motor.cogging_dq_comp.881 0 +motor.cogging_dq_comp.882 0 +motor.cogging_dq_comp.883 0 +motor.cogging_dq_comp.884 0 +motor.cogging_dq_comp.885 0 +motor.cogging_dq_comp.886 0 +motor.cogging_dq_comp.887 0 +motor.cogging_dq_comp.888 0 +motor.cogging_dq_comp.889 0 +motor.cogging_dq_comp.890 0 +motor.cogging_dq_comp.891 0 +motor.cogging_dq_comp.892 0 +motor.cogging_dq_comp.893 0 +motor.cogging_dq_comp.894 0 +motor.cogging_dq_comp.895 0 +motor.cogging_dq_comp.896 0 +motor.cogging_dq_comp.897 0 +motor.cogging_dq_comp.898 0 +motor.cogging_dq_comp.899 0 +motor.cogging_dq_comp.900 0 +motor.cogging_dq_comp.901 0 +motor.cogging_dq_comp.902 0 +motor.cogging_dq_comp.903 0 +motor.cogging_dq_comp.904 0 +motor.cogging_dq_comp.905 0 +motor.cogging_dq_comp.906 0 +motor.cogging_dq_comp.907 0 +motor.cogging_dq_comp.908 0 +motor.cogging_dq_comp.909 0 +motor.cogging_dq_comp.910 0 +motor.cogging_dq_comp.911 0 +motor.cogging_dq_comp.912 0 +motor.cogging_dq_comp.913 0 +motor.cogging_dq_comp.914 0 +motor.cogging_dq_comp.915 0 +motor.cogging_dq_comp.916 0 +motor.cogging_dq_comp.917 0 +motor.cogging_dq_comp.918 0 +motor.cogging_dq_comp.919 0 +motor.cogging_dq_comp.920 0 +motor.cogging_dq_comp.921 0 +motor.cogging_dq_comp.922 0 +motor.cogging_dq_comp.923 0 +motor.cogging_dq_comp.924 0 +motor.cogging_dq_comp.925 0 +motor.cogging_dq_comp.926 0 +motor.cogging_dq_comp.927 0 +motor.cogging_dq_comp.928 0 +motor.cogging_dq_comp.929 0 +motor.cogging_dq_comp.930 0 +motor.cogging_dq_comp.931 0 +motor.cogging_dq_comp.932 0 +motor.cogging_dq_comp.933 0 +motor.cogging_dq_comp.934 0 +motor.cogging_dq_comp.935 0 +motor.cogging_dq_comp.936 0 +motor.cogging_dq_comp.937 0 +motor.cogging_dq_comp.938 0 +motor.cogging_dq_comp.939 0 +motor.cogging_dq_comp.940 0 +motor.cogging_dq_comp.941 0 +motor.cogging_dq_comp.942 0 +motor.cogging_dq_comp.943 0 +motor.cogging_dq_comp.944 0 +motor.cogging_dq_comp.945 0 +motor.cogging_dq_comp.946 0 +motor.cogging_dq_comp.947 0 +motor.cogging_dq_comp.948 0 +motor.cogging_dq_comp.949 0 +motor.cogging_dq_comp.950 0 +motor.cogging_dq_comp.951 0 +motor.cogging_dq_comp.952 0 +motor.cogging_dq_comp.953 0 +motor.cogging_dq_comp.954 0 +motor.cogging_dq_comp.955 0 +motor.cogging_dq_comp.956 0 +motor.cogging_dq_comp.957 0 +motor.cogging_dq_comp.958 0 +motor.cogging_dq_comp.959 0 +motor.cogging_dq_comp.960 0 +motor.cogging_dq_comp.961 0 +motor.cogging_dq_comp.962 0 +motor.cogging_dq_comp.963 0 +motor.cogging_dq_comp.964 0 +motor.cogging_dq_comp.965 0 +motor.cogging_dq_comp.966 0 +motor.cogging_dq_comp.967 0 +motor.cogging_dq_comp.968 0 +motor.cogging_dq_comp.969 0 +motor.cogging_dq_comp.970 0 +motor.cogging_dq_comp.971 0 +motor.cogging_dq_comp.972 0 +motor.cogging_dq_comp.973 0 +motor.cogging_dq_comp.974 0 +motor.cogging_dq_comp.975 0 +motor.cogging_dq_comp.976 0 +motor.cogging_dq_comp.977 0 +motor.cogging_dq_comp.978 0 +motor.cogging_dq_comp.979 0 +motor.cogging_dq_comp.980 0 +motor.cogging_dq_comp.981 0 +motor.cogging_dq_comp.982 0 +motor.cogging_dq_comp.983 0 +motor.cogging_dq_comp.984 0 +motor.cogging_dq_comp.985 0 +motor.cogging_dq_comp.986 0 +motor.cogging_dq_comp.987 0 +motor.cogging_dq_comp.988 0 +motor.cogging_dq_comp.989 0 +motor.cogging_dq_comp.990 0 +motor.cogging_dq_comp.991 0 +motor.cogging_dq_comp.992 0 +motor.cogging_dq_comp.993 0 +motor.cogging_dq_comp.994 0 +motor.cogging_dq_comp.995 0 +motor.cogging_dq_comp.996 0 +motor.cogging_dq_comp.997 0 +motor.cogging_dq_comp.998 0 +motor.cogging_dq_comp.999 0 +motor.cogging_dq_comp.1000 0 +motor.cogging_dq_comp.1001 0 +motor.cogging_dq_comp.1002 0 +motor.cogging_dq_comp.1003 0 +motor.cogging_dq_comp.1004 0 +motor.cogging_dq_comp.1005 0 +motor.cogging_dq_comp.1006 0 +motor.cogging_dq_comp.1007 0 +motor.cogging_dq_comp.1008 0 +motor.cogging_dq_comp.1009 0 +motor.cogging_dq_comp.1010 0 +motor.cogging_dq_comp.1011 0 +motor.cogging_dq_comp.1012 0 +motor.cogging_dq_comp.1013 0 +motor.cogging_dq_comp.1014 0 +motor.cogging_dq_comp.1015 0 +motor.cogging_dq_comp.1016 0 +motor.cogging_dq_comp.1017 0 +motor.cogging_dq_comp.1018 0 +motor.cogging_dq_comp.1019 0 +motor.cogging_dq_comp.1020 0 +motor.cogging_dq_comp.1021 0 +motor.cogging_dq_comp.1022 0 +motor.cogging_dq_comp.1023 0 +drv8323_conf.dis_cpuv 0 +drv8323_conf.dis_gdf 0 +drv8323_conf.otw_rep 0 +drv8323_conf.pwm_mode 1 +drv8323_conf.pwm_1x_asynchronous 0 +drv8323_conf.pwm_1x_dir 0 +drv8323_conf.idrivep_hs_ma 100 +drv8323_conf.idriven_hs_ma 200 +drv8323_conf.cbc 1 +drv8323_conf.tdrive_ns 1000 +drv8323_conf.idrivep_ls_ma 100 +drv8323_conf.idriven_ls_ma 200 +drv8323_conf.tretry 0 +drv8323_conf.dead_time_ns 50 +drv8323_conf.ocp_mode 0 +drv8323_conf.ocp_deg_us 4 +drv8323_conf.vds_lvl_mv 700 +drv8323_conf.csa_fet 0 +drv8323_conf.vref_div 1 +drv8323_conf.ls_ref 0 +drv8323_conf.csa_gain 20 +drv8323_conf.dis_sen 0 +drv8323_conf.sen_lvl_mv 500 +servo.pwm_rate_hz 30000 +servo.i_gain 20.000000 +servo.current_sense_ohm 0.000500 +servo.pwm_comp_off 0.027000 +servo.pwm_comp_mag 0.005000 +servo.pwm_scale 1.000000 +servo.max_voltage 46.000000 +servo.max_power_W 450.000000 +servo.derate_temperature 50.000000 +servo.fault_temperature 75.000000 +servo.enable_motor_temperature 0 +servo.motor_derate_temperature 50.000000 +servo.motor_fault_temperature nan +servo.velocity_threshold 0.000000 +servo.position_derate 0.020000 +servo.adc_cur_cycles 2 +servo.adc_aux_cycles 47 +servo.pid_dq.kp 0.208156 +servo.pid_dq.ki 136.432968 +servo.pid_position.kp 0.500000 +servo.pid_position.ki 0.000000 +servo.pid_position.kd 0.050000 +servo.pid_position.iratelimit -1.000000 +servo.pid_position.ilimit 0.000000 +servo.pid_position.max_desired_rate 0.000000 +servo.pid_position.sign -1 +servo.current_feedforward 1.000000 +servo.bemf_feedforward 1.000000 +servo.default_velocity_limit nan +servo.default_accel_limit nan +servo.voltage_mode_control 0 +servo.fixed_voltage_mode 0 +servo.fixed_voltage_control_V 0.000000 +servo.max_position_slip 10.000000 +servo.default_timeout_s 0.100000 +servo.timeout_max_torque_Nm 5.000000 +servo.timeout_mode 12 +servo.flux_brake_min_voltage 43.500000 +servo.flux_brake_resistance_ohm 0.025000 +servo.max_current_A 7.500000 +servo.derate_current_A -20.000000 +servo.max_velocity 500.000000 +servo.max_velocity_derate 2.000000 +servo.cooldown_cycles 256 +servo.velocity_zero_capture_threshold 0.050000 +servo.emit_debug 0 +servopos.position_min nan +servopos.position_max nan +id.id 19 +can.prefix 0 + From 93f3f1992d6a42ac400287a5a856d59ed5731f35 Mon Sep 17 00:00:00 2001 From: qhdwight Date: Thu, 18 Apr 2024 17:03:06 -0400 Subject: [PATCH 08/10] Fix drive direction --- src/esw/drive_bridge/main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/esw/drive_bridge/main.cpp b/src/esw/drive_bridge/main.cpp index 4bcbe86d5..9e836e462 100644 --- a/src/esw/drive_bridge/main.cpp +++ b/src/esw/drive_bridge/main.cpp @@ -55,7 +55,7 @@ void moveDrive(geometry_msgs::Twist::ConstPtr const& msg) { { Velocity leftVelocity; leftVelocity.names = {"front_left", "middle_left", "back_left"}; - left *= -1; // TODO(quintin): Invert in firmware instead + leftVelocity.velocities.resize(leftVelocity.names.size(), left.get()); leftVelocity.velocities.resize(leftVelocity.names.size(), left.get()); leftVelocityPub.publish(leftVelocity); } From 1f0942a9321f83fcb75d4951da022a26aaabea31 Mon Sep 17 00:00:00 2001 From: qhdwight Date: Thu, 18 Apr 2024 17:22:02 -0400 Subject: [PATCH 09/10] Up max wheel speed --- config/esw.yaml | 26 +++++++++++++------------- src/teleoperation/backend/consumers.py | 7 ++++--- 2 files changed, 17 insertions(+), 16 deletions(-) diff --git a/config/esw.yaml b/config/esw.yaml index b29b86477..938d87a4d 100644 --- a/config/esw.yaml +++ b/config/esw.yaml @@ -96,23 +96,23 @@ can: brushless_motors: controllers: front_left: - min_velocity: -11.0 - max_velocity: 11.0 + min_velocity: -20.0 + max_velocity: 20.0 front_right: - min_velocity: -11.0 - max_velocity: 11.0 + min_velocity: -20.0 + max_velocity: 20.0 middle_left: - min_velocity: -11.0 - max_velocity: 11.0 + min_velocity: -20.0 + max_velocity: 20.0 middle_right: - min_velocity: -11.0 - max_velocity: 11.0 + min_velocity: -20.0 + max_velocity: 20.0 back_left: - min_velocity: -11.0 - max_velocity: 11.0 + min_velocity: -20.0 + max_velocity: 20.0 back_right: - min_velocity: -11.0 - max_velocity: 11.0 + min_velocity: -20.0 + max_velocity: 20.0 joint_a: # 1236.8475 rad/meter, or 196.850393476 rev/meter, and we want a max vel of 40 meter/s. # gear ratio is currently at 0.005080 revolutions = 1 meter @@ -499,7 +499,7 @@ cameras: rover: length: 0.86 width: 0.86 - max_speed: 2.0 + max_speed: 1.25 wheel: gear_ratio: 50.0 diff --git a/src/teleoperation/backend/consumers.py b/src/teleoperation/backend/consumers.py index 911c86f33..1b83fdea9 100644 --- a/src/teleoperation/backend/consumers.py +++ b/src/teleoperation/backend/consumers.py @@ -121,7 +121,8 @@ def connect(self): self.drive_config = rospy.get_param("teleop/drive_controls") self.max_wheel_speed = rospy.get_param("rover/max_speed") self.wheel_radius = rospy.get_param("wheel/radius") - self.max_angular_speed = self.max_wheel_speed / self.wheel_radius + self.rover_width = rospy.get_param("rover/width") + self.max_angular_speed = self.max_wheel_speed / (self.rover_width / 2) self.ra_config = rospy.get_param("teleop/ra_controls") self.ik_names = rospy.get_param("teleop/ik_multipliers") self.RA_NAMES = rospy.get_param("teleop/ra_names") @@ -426,10 +427,10 @@ def get_axes_input( signal *= scale return signal - linear = get_axes_input("forward_back", 0.05, True, self.max_wheel_speed * dampen) + linear = get_axes_input("forward_back", 0.02, True, self.max_wheel_speed * dampen) # Note(quintin): I prefer using solely the twist axis for turning... # angular_from_lateral = get_axes_input("left_right", 0.4, True) - angular = get_axes_input("twist", 0.1, True, self.max_angular_speed * dampen) + angular = get_axes_input("twist", 0.03, True, self.max_angular_speed * dampen) self.twist_pub.publish( Twist( From 54e0b98bafe428d2762019a194101e3a52bd8436 Mon Sep 17 00:00:00 2001 From: qhdwight Date: Thu, 18 Apr 2024 18:33:05 -0400 Subject: [PATCH 10/10] Up joint C max torque --- config/esw.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/config/esw.yaml b/config/esw.yaml index 938d87a4d..c7d84d40e 100644 --- a/config/esw.yaml +++ b/config/esw.yaml @@ -140,6 +140,7 @@ brushless_motors: max_velocity: 0.08 # max output shaft speed: 5 rpm (for now) min_position: -0.125 max_position: 0.30 # 220 degrees of motion is the entire range + max_torque: 20.0 joint_de_0: min_velocity: -5.0 max_velocity: 5.0