Skip to content

Commit e50a40b

Browse files
author
Richard Unger
committed
refactoring registers
1 parent 3a4d671 commit e50a40b

File tree

1 file changed

+6
-6
lines changed

1 file changed

+6
-6
lines changed

src/comms/SimpleFOCRegisters.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -473,22 +473,22 @@ bool SimpleFOCRegisters::commsToRegister(RegisterIO& comms, uint8_t reg, FOCMoto
473473
comms >> (motor->voltage_limit);
474474
if (motor->phase_resistance==NOT_SET){
475475
motor->PID_velocity.limit = motor->voltage_limit;
476-
if (motor->controller==MotionControlType::angle_nocascade)
477-
motor->P_angle.limit = motor->voltage_limit;
476+
//if (motor->controller==MotionControlType::angle_nocascade)
477+
// motor->P_angle.limit = motor->voltage_limit;
478478
}
479479
return true;
480480
case SimpleFOCRegister::REG_CURRENT_LIMIT:
481481
comms >> (motor->current_limit);
482482
if (motor->phase_resistance!=NOT_SET) {
483483
motor->PID_velocity.limit = motor->current_limit;
484-
if (motor->controller==MotionControlType::angle_nocascade)
485-
motor->P_angle.limit = motor->current_limit;
484+
//if (motor->controller==MotionControlType::angle_nocascade)
485+
// motor->P_angle.limit = motor->current_limit;
486486
}
487487
return true;
488488
case SimpleFOCRegister::REG_VELOCITY_LIMIT:
489489
comms >> (motor->velocity_limit);
490-
if (motor->controller!=MotionControlType::angle_nocascade)
491-
motor->P_angle.limit = motor->velocity_limit;
490+
//if (motor->controller!=MotionControlType::angle_nocascade)
491+
// motor->P_angle.limit = motor->velocity_limit;
492492
return true;
493493
case SimpleFOCRegister::REG_MOTION_DOWNSAMPLE:
494494
comms >> val8;

0 commit comments

Comments
 (0)