Skip to content

WoEN: AiR Into The Deep v3.0#4

Open
tikhonsmovzh wants to merge 48 commits intomasterfrom
develop
Open

WoEN: AiR Into The Deep v3.0#4
tikhonsmovzh wants to merge 48 commits intomasterfrom
develop

Conversation

@tikhonsmovzh
Copy link
Copy Markdown
Collaborator

финальный релиз программы робота 18742.

tikhonsmovzh and others added 30 commits February 9, 2025 14:22
tikhonsmovzh and others added 17 commits March 13, 2025 21:44
),
isAuto = true,
mutableListOf(/*ся модули для автонома*/ TrajectorySegmentRunner(), ActionsRunner())
mutableListOf(/*ся модули для автонома*/ TrajectorySegmentRunner(), ActionsRunner(), Camera())
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Поправить коммент


open class AutoOpMode(val startPos: GameStartPosition): LinearOpModeBase() {
override fun getOpModeSettings() = OpModeSettings(isAutoStart = false, isPreInit = false, preInitOpModeName = "TeleOpMode")
override fun getOpModeSettings() = OpModeSettings(isAutoStart = false, isPreInit = true, preInitOpModeName = "TeleOpMode", gamepadStart = false)
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Cделать вместо джавовского getXxx котлинский val с переопределенным геттером

Comment on lines +61 to +62
OpModeManagerImpl.getOpModeManagerOfActivity(AppUtil.getInstance().getActivity())
.startActiveOpMode()
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Обернуть в { }

if(!enableDetect.get()) {
allianceSticks.set(arrayOf())
override fun processFrame(frm: Mat?, captureTimeNanos: Long): Any {
//StaticTelemetry.addData("frameSize", frm!!.size())
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Избыточный вывод т.к. разрешение задаем мы. + неплохо бы его явно задать в Camera

Configs.CameraConfig.YELLOW_STICK_DETECT_CONFIG.KR,
Configs.CameraConfig.YELLOW_STICK_DETECT_CONFIG.KG,
Configs.CameraConfig.YELLOW_STICK_DETECT_CONFIG.KB,
Configs.CameraConfig.YELLOW_STICK_DETECT_CONFIG.THREASHOLD
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
Configs.CameraConfig.YELLOW_STICK_DETECT_CONFIG.THREASHOLD
Configs.CameraConfig.YELLOW_STICK_DETECT_CONFIG.THRESHOLD

class TurnSegment(angle: Double, private val _startOrientation: Orientation): ITrajectorySegment{
private val _turn = TimeTurn(Pose2d(_startOrientation.x, _startOrientation.y, _startOrientation.angl.angle), angle,
TurnConstraints(Configs.DriveTrainConfig.MAX_ROTATE_VELOCITY, -Configs.DriveTrainConfig.ROTATE_ACCEL, Configs.DriveTrainConfig.ROTATE_ACCEL))
TurnConstraints(Configs.RoadRunnerConfig.ROAD_RUNNER_ROTATE_VELOCITY, -Configs.RoadRunnerConfig.ROAD_RUNNER_ROTATE_VELOCITY, Configs.DriveTrainConfig.ROTATE_ACCEL))
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Слишком длинная строка

@@ -37,13 +37,15 @@ class IMUGyro: IRobotModule {

override fun update() {
if(_oldReadTime.milliseconds() > 1000.0 / Configs.GyroscopeConfig.READ_HZ && Configs.GyroscopeConfig.USE_GYRO) {
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Заменить миллисекунды на секунды

_oldReadTime.reset()

_eventBus.invoke(UpdateImuGyroEvent(rot, _imu.getRobotAngularVelocity(AngleUnit.RADIANS).xRotationRate.toDouble()))
_eventBus.invoke(UpdateImuGyroEvent(rot, angles.getRoll(AngleUnit.RADIANS), _imu.getRobotAngularVelocity(AngleUnit.RADIANS).xRotationRate.toDouble()))
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Слишком длинная строка

get() {
val value = ((analogInput.voltage / Configs.CurrentSensor.ANALOG_INPUT_MAX_VOLTADGE) * 2.0 - 1.0) * -maxSensorCurrent

return value - backgroundCurrent
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

То что вычитается - это свойство потребителя, а не самого датчика тока (у сервопривода помимо измеряемого мотора есть схема управления, которая постоянно что-то жрет, датчик тока тут ни при чем)

Comment on lines +7 to +12
class CurrentSensor(val analogInput: AnalogInput,
val maxSensorCurrent: Double = Configs.CurrentSensor.DEFAULT_SENSOR_MAX_CURRENT,
val backgroundCurrent: Double = Configs.CurrentSensor.DEFAULT_BACKGROUND_CURRENT) {
val current: Double
get() {
val value = ((analogInput.voltage / Configs.CurrentSensor.ANALOG_INPUT_MAX_VOLTADGE) * 2.0 - 1.0) * -maxSensorCurrent
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Странная (но рабочая :)) формула.
Нас на должен волновать максимально допустимый вольтаж аналогового порта (это свойсто аналогового порта, а не датчика тока)

Можно сделать гораздо проще и сделать вот какие константы: разрешение [Ампер/Вольт] - в нашем случае это 5.0/2.5 и сдвиг вольтажа (ожидаемый вольтаж при котором сила тока равна нулю, для нас это 2.5)

current = (voltage - VOLTAGE_OFFSET) * AMPS_PER_VOLT

@oaleksander
Copy link
Copy Markdown
Member

image
Можно попробовать автоматически отформатировать весь код (ПКМ по папке TeamCode, выбрать соответствующие галочки и фильтр на .kt файлы)

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants