From 98da93860bdaa2a36d10af2f7152813ab79c0ba3 Mon Sep 17 00:00:00 2001 From: Toby Yang Date: Wed, 13 Feb 2019 14:51:27 +0800 Subject: [PATCH 1/2] remove some annotations --- .../src/main/java/frc/robot/OI.java | 9 --- .../src/main/java/frc/robot/Robot.java | 55 ++----------------- .../java/frc/robot/subsystems/Chassis.java | 3 - 3 files changed, 5 insertions(+), 62 deletions(-) diff --git a/2019 Draft III/src/main/java/frc/robot/OI.java b/2019 Draft III/src/main/java/frc/robot/OI.java index 057f5bc..ceb70b7 100644 --- a/2019 Draft III/src/main/java/frc/robot/OI.java +++ b/2019 Draft III/src/main/java/frc/robot/OI.java @@ -1,9 +1,3 @@ -/** - * OI.java - * for creating joystick objects and assigning buttons to different commands. - * 在此处初始化控制手柄,并将手柄按键对应到机器人任务 (command) 上面。 - */ - package frc.robot; import edu.wpi.first.wpilibj.XboxController; @@ -23,13 +17,11 @@ public class OI { public static final XboxController stick_1 = new XboxController(1); /* create button objects, the last number is the id of the button, starting from 1 */ - /* 创建按钮对象,最后一个数字对应着 DS 上显示的按钮 ID ,从 1 开始 */ public static Button stick_0_A = new JoystickButton(stick_0, 1); public static Button stick_0_B = new JoystickButton(stick_0, 2); public static Button stick_0_X = new JoystickButton(stick_0, 3); public static Button stick_0_Y = new JoystickButton(stick_0, 4); - public static Button stick_1_A = new JoystickButton(stick_1, 1); public static Button stick_1_B = new JoystickButton(stick_1, 2); public static Button stick_1_X = new JoystickButton(stick_1, 3); @@ -39,7 +31,6 @@ public class OI { public OI() { /* binding buttons to commands */ - /* 将任务 (command) 绑定到按钮 */ stick_0_A.whileHeld(new IntakeCollect(0.4)); stick_0_B.whileHeld(new IntakeCollect(-0.8)); stick_0_X.whenPressed(new IntakeLiftTo(3849)); diff --git a/2019 Draft III/src/main/java/frc/robot/Robot.java b/2019 Draft III/src/main/java/frc/robot/Robot.java index 6acdd1c..f4492a6 100644 --- a/2019 Draft III/src/main/java/frc/robot/Robot.java +++ b/2019 Draft III/src/main/java/frc/robot/Robot.java @@ -1,9 +1,3 @@ -/** - * Robot.java - * the entry class for the robot code. - * 机器人程序从这里开始。 - */ - package frc.robot; import edu.wpi.cscore.UsbCamera; @@ -22,8 +16,7 @@ import frc.robot.subsystems.Intake; public class Robot extends TimedRobot { - /* create subsystem objects */ - /* 创建子系统的实例 */ + // create subsystem objects public static Chassis chassis = new Chassis(); public static Arm arm = new Arm(); public static Claw claw = new Claw(); @@ -35,38 +28,25 @@ public class Robot extends TimedRobot { Command m_autonomousCommand; SendableChooser m_chooser = new SendableChooser<>(); - /** - * This function is called when the robot is first powered up or the code - * is restarted. - * 这段代码会在机器人上电或程序重启的时候执行一遍。 - */ + @Override public void robotInit() { /* initialize two cameras, one for vision processing and one for the driver. */ UsbCamera aliment_cam = CameraServer.getInstance().startAutomaticCapture(0); - // TODO: codes for CV. + // codes for CV. // UsbCamera driver_cam = CameraServer.getInstance().startAutomaticCapture(1); // driver_cam.setResolution(640, 480); - // m_chooser.setDefaultOption("Default Auto", new ExampleCommand()); // chooser.addOption("My Auto", new MyAutoCommand()); SmartDashboard.putData("Auto mode", m_chooser); - /* !!!!!!!!!!!!!!!!!!!!!!!!!!! */ + arm.resetSensor(); } - /** - * This function is called every robot packet, no matter the mode. Use - * this for items like diagnostics that you want ran during disabled, - * autonomous, teleoperated and test. It runs after the mode specific - * periodic functions, but before LiveWindow and SmartDashboard integrated - * updating. - * 这段代码将会在机器人通电的时候反复运行。运行顺序是在模式程序之后, LiveWindow - * 和 SD 更新数据之前。 - */ + @Override public void robotPeriodic() { arm.log(); @@ -76,11 +56,6 @@ public void robotPeriodic() { intake.log(); } - /** - * This function is called once each time the robot enters Disabled mode. - * You can use it to reset any subsystem information you want to clear when - * the robot is disabled. - */ @Override public void disabledInit() { } @@ -90,17 +65,6 @@ public void disabledPeriodic() { Scheduler.getInstance().run(); } - /** - * This autonomous (along with the chooser code above) shows how to select - * between different autonomous modes using the dashboard. The sendable - * chooser code works with the Java SmartDashboard. If you prefer the - * LabVIEW Dashboard, remove all of the chooser code and uncomment the - * getString code to get the auto name from the text box below the Gyro - * - * You can add additional auto modes by adding additional commands to the - * chooser code above (like the commented example) or additional comparisons - * to the switch structure below with additional strings & commands. - */ @Override public void autonomousInit() { m_autonomousCommand = m_chooser.getSelected(); @@ -118,9 +82,6 @@ public void autonomousInit() { } } - /** - * This function is called periodically during autonomous. - */ @Override public void autonomousPeriodic() { Scheduler.getInstance().run(); @@ -138,17 +99,11 @@ public void teleopInit() { } } - /** - * This function is called periodically during operator control. - */ @Override public void teleopPeriodic() { Scheduler.getInstance().run(); } - /** - * This function is called periodically during test mode. - */ @Override public void testPeriodic() { claw.enable_pid = false; diff --git a/2019 Draft III/src/main/java/frc/robot/subsystems/Chassis.java b/2019 Draft III/src/main/java/frc/robot/subsystems/Chassis.java index dd3e796..b34aadc 100644 --- a/2019 Draft III/src/main/java/frc/robot/subsystems/Chassis.java +++ b/2019 Draft III/src/main/java/frc/robot/subsystems/Chassis.java @@ -23,11 +23,9 @@ public class Chassis extends Subsystem { private SpeedController motor_roller = new Spark(RobotMap.p_PWM_chassis_roller); /* using the 'default FRC gyro' */ - /* 使用的是默认的插在RIO上的陀螺仪 */ private ADXRS450_Gyro gyro = new ADXRS450_Gyro(); /* the coefficient for the speed of the chassis motor */ - /* 电机速度系数,用来控制全局电机最大转速 */ public double global_y_speed = 0.7; public double global_z_speed = 0.4; @@ -35,7 +33,6 @@ public Chassis() { super(); /* correct the direction of motor: forward is positive */ - /* 修正电机方向,向前为正 */ motor_left_0.setInverted(false); motor_left_1.setInverted(false); motor_left_2.setInverted(false); From 5d63b69e86192e21865fbef203f0ecc7ce579973 Mon Sep 17 00:00:00 2001 From: Toby Yang Date: Wed, 13 Feb 2019 18:01:56 +0800 Subject: [PATCH 2/2] fixed some incorrect annotations moved all static parameters to RobotMap.java and renamed some variables --- .../src/main/java/frc/robot/RobotMap.java | 10 ++++++++ .../java/frc/robot/commands/ArmLiftTo.java | 2 +- .../main/java/frc/robot/subsystems/Arm.java | 24 +++++++++++-------- .../java/frc/robot/subsystems/Chassis.java | 4 ++-- .../main/java/frc/robot/subsystems/Claw.java | 20 ++++++++-------- .../main/java/frc/robot/subsystems/Hook.java | 4 ++-- .../java/frc/robot/subsystems/Intake.java | 2 +- 7 files changed, 40 insertions(+), 26 deletions(-) diff --git a/2019 Draft III/src/main/java/frc/robot/RobotMap.java b/2019 Draft III/src/main/java/frc/robot/RobotMap.java index 1a0d8aa..6bcc4f7 100644 --- a/2019 Draft III/src/main/java/frc/robot/RobotMap.java +++ b/2019 Draft III/src/main/java/frc/robot/RobotMap.java @@ -17,21 +17,31 @@ public class RobotMap { public static final int[] p_CAN_chassis_right = {13, 14, 15}; public static final int p_PWM_chassis_roller = 0; public static final int p_PEN_lift_up = 0; + public static final double chassis_speed_z = 0.4; + public static final double chassis_speed_y = 0.7; /* Arm */ public static final int[] p_CAN_arm = {20, 21}; + public static final double[] arm_speed = {0.6, 0.4}; + public static final double arm_kP = 0.003, arm_kD = 0.0001; /* Claw */ public static final int p_CAN_claw = 22; public static final int p_PWM_claw_shooter = 1; public static final int p_DIG_limit = 0; + public static final double claw_speed = 0.6; + public static final double claw_kP = 0.01; + public static final double claw_adjust_intensity = 10; /* Hook */ public static final int p_PWM_hook_servo = 9; public static final int p_PEN_hook_extender = 0; + public static final double hook_servo_open_ang = 0.3; + public static final double hook_servo_close_ang = 0.9; /* Intake */ public static final int p_PWM_intake_lift = 2; public static final int p_PWM_intake_collector = 3; public static final int p_ANA_intake_encoder = 0; + public static final double intake_global_lift_speed = 0.8; } diff --git a/2019 Draft III/src/main/java/frc/robot/commands/ArmLiftTo.java b/2019 Draft III/src/main/java/frc/robot/commands/ArmLiftTo.java index a8b23fe..d684716 100644 --- a/2019 Draft III/src/main/java/frc/robot/commands/ArmLiftTo.java +++ b/2019 Draft III/src/main/java/frc/robot/commands/ArmLiftTo.java @@ -19,7 +19,7 @@ public ArmLiftTo(double tar) { @Override protected void execute() { /* 0212: PID算法,现在只加了P,先试试效果 */ - Robot.arm.setSetpoint(tar_); + Robot.arm.setTarget(tar_); Robot.arm.setVel(Robot.arm.getPID()); } diff --git a/2019 Draft III/src/main/java/frc/robot/subsystems/Arm.java b/2019 Draft III/src/main/java/frc/robot/subsystems/Arm.java index b943e72..97a3479 100644 --- a/2019 Draft III/src/main/java/frc/robot/subsystems/Arm.java +++ b/2019 Draft III/src/main/java/frc/robot/subsystems/Arm.java @@ -17,11 +17,12 @@ public class Arm extends Subsystem { private TalonSRX motor_arm_left = new TalonSRX(RobotMap.p_CAN_arm[0]); private TalonSRX motor_arm_right = new TalonSRX(RobotMap.p_CAN_arm[1]); - private DigitalInput arm_limit_sw = new DigitalInput(RobotMap.p_DIG_limit); - public double[] global_arm_speed = {0.6, 0.4}; - private final double kP = 0.003, kD = 0.0001; - private double setpoint = 0; + private DigitalInput end_stop = new DigitalInput(RobotMap.p_DIG_limit); + public double[] global_arm_speed = RobotMap.arm_speed; + + private final double kP = RobotMap.arm_kP, kD = RobotMap.arm_kD; + private double target = 0; public Arm() { super(); @@ -31,27 +32,30 @@ public Arm() { public void resetSensor() { motor_arm_left.setSelectedSensorPosition(0); + // motor_arm_right.setSelectedSensorPosition(0); } public double getPos() { return -motor_arm_left.getSelectedSensorPosition(); + // return motor_arm_right.getSelectedSensorPosition(); } public double getVel() { return -motor_arm_left.getSelectedSensorVelocity(); + // return motor_arm_right.getSelectedSensorVelocity(); } public double getPID() { /* 0212: PID算法,现在只加了P,先试试效果 */ - double error = setpoint - getPos(); + double error = target - getPos(); double vel = kP * error - kD * getVel(); vel = Math.max(-1.2, Math.min(1.2, vel)); return vel; } - public void setSetpoint(double val) { - setpoint = val; + public void setTarget(double val) { + target = val; } public void setVel(double vel) { @@ -61,7 +65,7 @@ public void setVel(double vel) { motor_arm_right.set(ControlMode.PercentOutput, global_arm_speed[0] * vel); } else { /* downward */ - if (!arm_limit_sw.get()) { + if (!end_stop.get()) { motor_arm_left.set(ControlMode.PercentOutput, 0); motor_arm_right.set(ControlMode.PercentOutput, 0); } else { @@ -73,8 +77,8 @@ public void setVel(double vel) { public void log() { SmartDashboard.putNumber("Arm Position", getPos()); - SmartDashboard.putNumber("Arm Setpoint", setpoint); - SmartDashboard.putBoolean("Arm Limit", arm_limit_sw.get()); + SmartDashboard.putNumber("Arm Setpoint", target); + SmartDashboard.putBoolean("Arm Limit", end_stop.get()); } @Override diff --git a/2019 Draft III/src/main/java/frc/robot/subsystems/Chassis.java b/2019 Draft III/src/main/java/frc/robot/subsystems/Chassis.java index b34aadc..ae1bf24 100644 --- a/2019 Draft III/src/main/java/frc/robot/subsystems/Chassis.java +++ b/2019 Draft III/src/main/java/frc/robot/subsystems/Chassis.java @@ -26,8 +26,8 @@ public class Chassis extends Subsystem { private ADXRS450_Gyro gyro = new ADXRS450_Gyro(); /* the coefficient for the speed of the chassis motor */ - public double global_y_speed = 0.7; - public double global_z_speed = 0.4; + public double global_y_speed = RobotMap.chassis_speed_y; + public double global_z_speed = RobotMap.chassis_speed_z; public Chassis() { super(); diff --git a/2019 Draft III/src/main/java/frc/robot/subsystems/Claw.java b/2019 Draft III/src/main/java/frc/robot/subsystems/Claw.java index 7c133b7..6a57845 100644 --- a/2019 Draft III/src/main/java/frc/robot/subsystems/Claw.java +++ b/2019 Draft III/src/main/java/frc/robot/subsystems/Claw.java @@ -1,6 +1,6 @@ /** - * Arm.java - * contains motors with encoders for both arm and claw + * Claw.java + * contains motors with encoders for claw * */ @@ -18,13 +18,13 @@ public class Claw extends Subsystem { private TalonSRX lift_motor = new TalonSRX(RobotMap.p_CAN_claw); private SpeedController shooter_motor = new VictorSP(RobotMap.p_PWM_claw_shooter); - public double global_claw_speed = 0.6; + public double global_claw_speed = RobotMap.claw_speed; - private final double kP = 0.01; - private double setpoint = 0; + private final double kP = RobotMap.claw_kP; + private double target = 0; public boolean enable_pid = true; - public double adjust_intensity = 10; + public double adjust_intensity = RobotMap.claw_adjust_intensity; public Claw() { super(); @@ -41,18 +41,18 @@ public double getPos() { } public double getPID() { - double error = setpoint - getPos(); + double error = target - getPos(); double vel = kP * error; vel = Math.max(-1.5, Math.min(1.5, vel)); return vel; } public void adjustSetpoint(double val) { - setpoint += adjust_intensity * val; + target += adjust_intensity * val; } public void setSetpoint(double val) { - setpoint = val; + target = val; } public void setVel(double vel) { @@ -65,7 +65,7 @@ public void setShooterVel(double vel) { public void log() { SmartDashboard.putNumber("Claw Position", getPos()); - SmartDashboard.putNumber("Claw Setpoint", setpoint); + SmartDashboard.putNumber("Claw Setpoint", target); } @Override diff --git a/2019 Draft III/src/main/java/frc/robot/subsystems/Hook.java b/2019 Draft III/src/main/java/frc/robot/subsystems/Hook.java index 03328fa..1ae1517 100644 --- a/2019 Draft III/src/main/java/frc/robot/subsystems/Hook.java +++ b/2019 Draft III/src/main/java/frc/robot/subsystems/Hook.java @@ -15,8 +15,8 @@ public class Hook extends Subsystem { private Solenoid hook_extender = new Solenoid(RobotMap.p_PEN_hook_extender); private Servo hook = new Servo(RobotMap.p_PWM_hook_servo); - public static final double servo_open_ang = 0.3; - public static final double servo_close_ang = 0.9; + public static final double servo_open_ang = RobotMap.hook_servo_open_ang; + public static final double servo_close_ang = RobotMap.hook_servo_close_ang; public Hook() { super(); diff --git a/2019 Draft III/src/main/java/frc/robot/subsystems/Intake.java b/2019 Draft III/src/main/java/frc/robot/subsystems/Intake.java index a2dd917..5635e99 100644 --- a/2019 Draft III/src/main/java/frc/robot/subsystems/Intake.java +++ b/2019 Draft III/src/main/java/frc/robot/subsystems/Intake.java @@ -17,7 +17,7 @@ public class Intake extends Subsystem { private SpeedController motor_lift = new Spark(RobotMap.p_PWM_intake_lift); private SpeedController motor_collector = new Spark(RobotMap.p_PWM_intake_collector); private AnalogInput lift_sensor = new AnalogInput(RobotMap.p_ANA_intake_encoder); - public double global_lift_speed = 0.8; + public double global_lift_speed = RobotMap.intake_global_lift_speed; public Intake() { super();