diff --git a/FRC_20230317_012002.wpilog b/FRC_20230317_012002.wpilog new file mode 100644 index 0000000..d8700ae Binary files /dev/null and b/FRC_20230317_012002.wpilog differ diff --git a/FRC_20230317_013122.wpilog b/FRC_20230317_013122.wpilog new file mode 100644 index 0000000..9ca6fa8 Binary files /dev/null and b/FRC_20230317_013122.wpilog differ diff --git a/FRC_20230317_013512.wpilog b/FRC_20230317_013512.wpilog new file mode 100644 index 0000000..7dc3b50 Binary files /dev/null and b/FRC_20230317_013512.wpilog differ diff --git a/FRC_20230317_013643.wpilog b/FRC_20230317_013643.wpilog new file mode 100644 index 0000000..b07438a Binary files /dev/null and b/FRC_20230317_013643.wpilog differ diff --git a/final-final-final.json b/final-final-final.json new file mode 100644 index 0000000..ae0155b --- /dev/null +++ b/final-final-final.json @@ -0,0 +1,499 @@ +{ + "tabPane": [ + { + "title": "Main", + "autoPopulate": false, + "autoPopulatePrefix": "LiveWindow/", + "widgetPane": { + "gridSize": 32.0, + "showGrid": true, + "hgap": 16.0, + "vgap": 16.0, + "titleType": 2, + "tiles": { + "0,0": { + "size": [ + 8, + 3 + ], + "content": { + "_type": "Basic FMS Info", + "_source0": "network_table:///FMSInfo", + "_title": "Info", + "_glyph": 148, + "_showGlyph": false + } + }, + "0,3": { + "size": [ + 8, + 11 + ], + "content": { + "_type": "PDP", + "_source0": "network_table:///Shuffleboard/PDP/PDP", + "_title": "PDP", + "_glyph": 148, + "_showGlyph": false, + "Visuals/Show voltage and current values": true + } + }, + "26,0": { + "size": [ + 5, + 8 + ], + "content": { + "_type": "Subsystem Layout", + "_title": "Arm System", + "_glyph": 149, + "_showGlyph": false, + "Layout/Label position": "BOTTOM", + "_children": [ + { + "_type": "Number Bar", + "_source0": "network_table:///Shuffleboard/Motors/Claw/Applied Output", + "_title": "Claw", + "_glyph": 148, + "_showGlyph": false, + "Range/Min": -1.0, + "Range/Max": 1.0, + "Range/Center": 0.0, + "Visuals/Num tick marks": 5, + "Visuals/Show text": true, + "Visuals/Orientation": "HORIZONTAL" + }, + { + "_type": "Number Bar", + "_source0": "network_table:///Shuffleboard/Motors/Turret/Applied Output", + "_title": "Turret", + "_glyph": 148, + "_showGlyph": false, + "Range/Min": -1.0, + "Range/Max": 1.0, + "Range/Center": 0.0, + "Visuals/Num tick marks": 5, + "Visuals/Show text": true, + "Visuals/Orientation": "HORIZONTAL" + }, + { + "_type": "Number Bar", + "_source0": "network_table:///Shuffleboard/Motors/Arm/Applied Output", + "_title": "Arm", + "_glyph": 148, + "_showGlyph": false, + "Range/Min": -1.0, + "Range/Max": 1.0, + "Range/Center": 0.0, + "Visuals/Num tick marks": 5, + "Visuals/Show text": true, + "Visuals/Orientation": "HORIZONTAL" + } + ] + } + }, + "8,0": { + "size": [ + 9, + 8 + ], + "content": { + "_type": "Camera Stream", + "_source0": "camera_server://Arm", + "_title": "Arm", + "_glyph": 148, + "_showGlyph": false, + "Crosshair/Show crosshair": true, + "Crosshair/Crosshair color": "#FFFFFFFF", + "Controls/Show controls": true, + "Controls/Rotation": "HALF", + "compression": 35.0, + "fps": 15, + "imageWidth": 640, + "imageHeight": 480 + } + }, + "17,0": { + "size": [ + 9, + 8 + ], + "content": { + "_type": "Camera Stream", + "_source0": "camera_server://limelight", + "_title": "limelight", + "_glyph": 148, + "_showGlyph": false, + "Crosshair/Show crosshair": true, + "Crosshair/Crosshair color": "#FFFFFFFF", + "Controls/Show controls": true, + "Controls/Rotation": "HALF", + "compression": 27.0, + "fps": -1, + "imageWidth": -1, + "imageHeight": -1 + } + }, + "12,8": { + "size": [ + 19, + 7 + ], + "content": { + "_type": "Graph", + "_source0": "network_table:///FMSInfo/FMSControlData", + "_source1": "network_table:///Shuffleboard/PDP/PDP/Voltage", + "_title": "Voltage", + "_glyph": 148, + "_showGlyph": false, + "Graph/Visible time": 60.0, + "Graph/X-axis auto scrolling": true, + "Y-axis/Automatic bounds": false, + "Y-axis/Upper bound": 13.0, + "Y-axis/Lower bound": 6.0, + "Y-axis/Unit": "v", + "Visible data/FMSInfo/FMSControlData": true, + "Visible data/Shuffleboard/PDP/PDP/Voltage": true + } + }, + "9,10": { + "size": [ + 3, + 3 + ], + "content": { + "_type": "Number Bar", + "_source0": "network_table:///Shuffleboard/Config/Tank/Max Speed", + "_title": "Shuffleboard/Config/Tank/Max Speed", + "_glyph": 148, + "_showGlyph": false, + "Range/Min": 0.0, + "Range/Max": 1.0, + "Range/Center": 0.0, + "Visuals/Num tick marks": 5, + "Visuals/Show text": true, + "Visuals/Orientation": "HORIZONTAL" + } + }, + "9,8": { + "size": [ + 2, + 1 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///FMSInfo/FMSControlData", + "_title": "/FMSInfo/FMSControlData", + "_glyph": 148, + "_showGlyph": false + } + } + } + } + }, + { + "title": "Tab 7", + "autoPopulate": true, + "autoPopulatePrefix": "SmartDashboard/", + "widgetPane": { + "gridSize": 8.0, + "showGrid": true, + "hgap": 16.0, + "vgap": 16.0, + "titleType": 0, + "tiles": { + "0,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/limelight_PipelineName", + "_title": "rtDashboard/limelight_PipelineName", + "_glyph": 148, + "_showGlyph": false + } + }, + "4,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/limelight_Interface", + "_title": "rtDashboard/limelight_Interface", + "_glyph": 148, + "_showGlyph": false + } + }, + "8,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/limelight_Stream", + "_title": "rtDashboard/limelight_Stream", + "_glyph": 148, + "_showGlyph": false + } + }, + "12,0": { + "size": [ + 6, + 6 + ], + "content": { + "_type": "Boolean Box", + "_source0": "network_table:///SmartDashboard/brakeMode", + "_title": "rtDashboard/brakeMode", + "_glyph": 148, + "_showGlyph": false, + "Colors/Color when true": "#7CFC00FF", + "Colors/Color when false": "#8B0000FF" + } + }, + "18,0": { + "size": [ + 6, + 6 + ], + "content": { + "_type": "Boolean Box", + "_source0": "network_table:///SmartDashboard/zeroDeg", + "_title": "rtDashboard/zeroDeg", + "_glyph": 148, + "_showGlyph": false, + "Colors/Color when true": "#7CFC00FF", + "Colors/Color when false": "#8B0000FF" + } + }, + "24,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/leftStickY", + "_title": "rtDashboard/leftStickY", + "_glyph": 148, + "_showGlyph": false + } + }, + "28,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/rightStickX", + "_title": "rtDashboard/rightStickX", + "_glyph": 148, + "_showGlyph": false + } + }, + "32,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/pitch angle", + "_title": "rtDashboard/pitch angle", + "_glyph": 148, + "_showGlyph": false + } + }, + "36,0": { + "size": [ + 6, + 6 + ], + "content": { + "_type": "Boolean Box", + "_source0": "network_table:///SmartDashboard/gyro cal", + "_title": "rtDashboard/gyro cal", + "_glyph": 148, + "_showGlyph": false, + "Colors/Color when true": "#7CFC00FF", + "Colors/Color when false": "#8B0000FF" + } + }, + "42,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/yaw angle", + "_title": "rtDashboard/yaw angle", + "_glyph": 148, + "_showGlyph": false + } + }, + "46,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/pitch offset", + "_title": "rtDashboard/pitch offset", + "_glyph": 148, + "_showGlyph": false + } + }, + "50,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/PDP Voltage", + "_title": "rtDashboard/PDP Voltage", + "_glyph": 148, + "_showGlyph": false + } + }, + "54,0": { + "size": [ + 12, + 22 + ], + "content": { + "_type": "Subsystem Layout", + "_source0": "network_table:///SmartDashboard/Scheduler/Ids", + "_title": "rtDashboard/Scheduler/Ids", + "_glyph": 149, + "_showGlyph": false, + "Layout/Label position": "BOTTOM", + "_children": [] + } + }, + "0,2": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/maxSpeed", + "_title": "rtDashboard/maxSpeed", + "_glyph": 148, + "_showGlyph": false + } + }, + "4,2": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/init pitch", + "_title": "rtDashboard/init pitch", + "_glyph": 148, + "_showGlyph": false + } + }, + "8,2": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/max offset", + "_title": "rtDashboard/max offset", + "_glyph": 148, + "_showGlyph": false + } + }, + "24,2": { + "size": [ + 6, + 6 + ], + "content": { + "_type": "Boolean Box", + "_source0": "network_table:///SmartDashboard/onRamp", + "_title": "rtDashboard/onRamp", + "_glyph": 148, + "_showGlyph": false, + "Colors/Color when true": "#7CFC00FF", + "Colors/Color when false": "#8B0000FF" + } + }, + "30,2": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/motor speed", + "_title": "rtDashboard/motor speed", + "_glyph": 148, + "_showGlyph": false + } + }, + "30,13": { + "size": [ + 6, + 10 + ], + "content": { + "_type": "Network Table Tree", + "_source0": "network_table:///FMSInfo", + "_title": "/FMSInfo", + "_glyph": 148, + "_showGlyph": false + } + } + } + } + }, + { + "title": "Tab 8", + "autoPopulate": false, + "autoPopulatePrefix": "", + "widgetPane": { + "gridSize": 32.0, + "showGrid": true, + "hgap": 16.0, + "vgap": 16.0, + "titleType": 0, + "tiles": { + "14,3": { + "size": [ + 9, + 9 + ], + "content": { + "_type": "Network Table Tree", + "_source0": "network_table:///FMSInfo", + "_title": "/FMSInfo", + "_glyph": 148, + "_showGlyph": false + } + } + } + } + } + ], + "windowGeometry": { + "x": -7.199999809265137, + "y": -7.199999809265137, + "width": 1550.4000244140625, + "height": 838.4000244140625 + } +} \ No newline at end of file diff --git a/final-final.json b/final-final.json new file mode 100644 index 0000000..082d434 --- /dev/null +++ b/final-final.json @@ -0,0 +1,554 @@ +{ + "tabPane": [ + { + "title": "SmartDashboard", + "autoPopulate": true, + "autoPopulatePrefix": "SmartDashboard/", + "widgetPane": { + "gridSize": 32.0, + "showGrid": true, + "hgap": 16.0, + "vgap": 16.0, + "titleType": 0, + "tiles": { + "0,0": { + "size": [ + 6, + 6 + ], + "content": { + "_type": "Boolean Box", + "_source0": "network_table:///SmartDashboard/brakeMode", + "_title": "brakeMode", + "_glyph": 148, + "_showGlyph": false, + "Colors/Color when true": "#7CFC00FF", + "Colors/Color when false": "#8B0000FF" + } + }, + "2,0": { + "size": [ + 6, + 6 + ], + "content": { + "_type": "Boolean Box", + "_source0": "network_table:///SmartDashboard/zeroDeg", + "_title": "zeroDeg", + "_glyph": 148, + "_showGlyph": false, + "Colors/Color when true": "#7CFC00FF", + "Colors/Color when false": "#8B0000FF" + } + }, + "4,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/leftStickY", + "_title": "leftStickY", + "_glyph": 148, + "_showGlyph": false + } + }, + "6,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/rightStickX", + "_title": "rightStickX", + "_glyph": 148, + "_showGlyph": false + } + }, + "8,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/pitch angle", + "_title": "pitch angle", + "_glyph": 148, + "_showGlyph": false + } + }, + "1,0": { + "size": [ + 6, + 6 + ], + "content": { + "_type": "Boolean Box", + "_source0": "network_table:///SmartDashboard/gyro cal", + "_title": "gyro cal", + "_glyph": 148, + "_showGlyph": false, + "Colors/Color when true": "#7CFC00FF", + "Colors/Color when false": "#8B0000FF" + } + }, + "3,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/yaw angle", + "_title": "yaw angle", + "_glyph": 148, + "_showGlyph": false + } + }, + "5,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/pitch offset", + "_title": "pitch offset", + "_glyph": 148, + "_showGlyph": false + } + }, + "7,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/PDP Voltage", + "_title": "PDP Voltage", + "_glyph": 148, + "_showGlyph": false + } + }, + "9,0": { + "size": [ + 12, + 22 + ], + "content": { + "_type": "Subsystem Layout", + "_source0": "network_table:///SmartDashboard/Scheduler/Ids", + "_title": "Scheduler/Ids", + "_glyph": 149, + "_showGlyph": false, + "Layout/Label position": "BOTTOM", + "_children": [] + } + }, + "10,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/maxSpeed", + "_title": "maxSpeed", + "_glyph": 148, + "_showGlyph": false + } + }, + "11,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/init pitch", + "_title": "init pitch", + "_glyph": 148, + "_showGlyph": false + } + }, + "12,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/max offset", + "_title": "max offset", + "_glyph": 148, + "_showGlyph": false + } + }, + "12,2": { + "size": [ + 6, + 6 + ], + "content": { + "_type": "Boolean Box", + "_source0": "network_table:///SmartDashboard/onRamp", + "_title": "onRamp", + "_glyph": 148, + "_showGlyph": false, + "Colors/Color when true": "#7CFC00FF", + "Colors/Color when false": "#8B0000FF" + } + }, + "28,16": { + "size": [ + 9, + 9 + ], + "content": { + "_type": "Gyro", + "_source0": "network_table:///Shuffleboard/Driver/Gyro", + "_title": "/Shuffleboard/Driver/Gyro", + "_glyph": 148, + "_showGlyph": false, + "Visuals/Major tick spacing": 45.0, + "Visuals/Starting angle": 180.0, + "Visuals/Show tick mark ring": true, + "Visuals/Counter clockwise": false + } + }, + "66,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/limelight_PipelineName", + "_title": "limelight_PipelineName", + "_glyph": 148, + "_showGlyph": false + } + }, + "70,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/limelight_Interface", + "_title": "limelight_Interface", + "_glyph": 148, + "_showGlyph": false + } + }, + "74,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/limelight_Stream", + "_title": "limelight_Stream", + "_glyph": 148, + "_showGlyph": false + } + }, + "78,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/averageD", + "_title": "averageD", + "_glyph": 148, + "_showGlyph": false + } + }, + "82,0": { + "size": [ + 4, + 2 + ], + "content": { + "_type": "Text View", + "_source0": "network_table:///SmartDashboard/motor speed", + "_title": "motor speed", + "_glyph": 148, + "_showGlyph": false + } + } + } + } + }, + { + "title": "Main", + "autoPopulate": false, + "autoPopulatePrefix": "LiveWindow/", + "widgetPane": { + "gridSize": 32.0, + "showGrid": true, + "hgap": 16.0, + "vgap": 16.0, + "titleType": 1, + "tiles": { + "0,0": { + "size": [ + 8, + 3 + ], + "content": { + "_type": "Basic FMS Info", + "_source0": "network_table:///FMSInfo", + "_title": "Info", + "_glyph": 148, + "_showGlyph": false + } + }, + "0,3": { + "size": [ + 8, + 11 + ], + "content": { + "_type": "PDP", + "_source0": "network_table:///Shuffleboard/PDP/PDP", + "_title": "PDP", + "_glyph": 148, + "_showGlyph": false, + "Visuals/Show voltage and current values": true + } + }, + "22,0": { + "size": [ + 4, + 8 + ], + "content": { + "_type": "List Layout", + "_title": "Misc", + "_glyph": 149, + "_showGlyph": false, + "Layout/Label position": "BOTTOM", + "_children": [ + { + "_type": "Boolean Box", + "_source0": "network_table:///SmartDashboard/zeroDeg", + "_title": "0 Degres?", + "_glyph": 148, + "_showGlyph": false, + "Colors/Color when true": "#7CFC00FF", + "Colors/Color when false": "#8B0000FF" + }, + { + "_type": "Boolean Box", + "_source0": "network_table:///SmartDashboard/brakeMode", + "_title": "Brake Mode", + "_glyph": 148, + "_showGlyph": false, + "Colors/Color when true": "#7CFC00FF", + "Colors/Color when false": "#8B0000FF" + }, + { + "_type": "Number Bar", + "_source0": "network_table:///Shuffleboard/Config/Tank/Max Speed", + "_title": "Max Speed", + "_glyph": 148, + "_showGlyph": false, + "Range/Min": 0.0, + "Range/Max": 1.0, + "Range/Center": 0.0, + "Visuals/Num tick marks": 5, + "Visuals/Show text": true, + "Visuals/Orientation": "HORIZONTAL" + }, + { + "_type": "Number Bar", + "_source0": "network_table:///SmartDashboard/rightStickX", + "_title": "Right Stick X", + "_glyph": 148, + "_showGlyph": false, + "Range/Min": -1.0, + "Range/Max": 1.0, + "Range/Center": 0.0, + "Visuals/Num tick marks": 5, + "Visuals/Show text": true, + "Visuals/Orientation": "HORIZONTAL" + } + ] + } + }, + "22,8": { + "size": [ + 9, + 6 + ], + "content": { + "_type": "Differential Drivebase", + "_source0": "network_table:///Shuffleboard/Motors/Drive", + "_title": "Drivebase", + "_glyph": 148, + "_showGlyph": false, + "Wheels/Number of wheels": 4, + "Wheels/Wheel diameter": 80.0, + "Visuals/Show velocity vectors": true + } + }, + "26,0": { + "size": [ + 5, + 8 + ], + "content": { + "_type": "Subsystem Layout", + "_title": "Arm System", + "_glyph": 149, + "_showGlyph": false, + "Layout/Label position": "BOTTOM", + "_children": [ + { + "_type": "Number Bar", + "_source0": "network_table:///Shuffleboard/Motors/Claw/Applied Output", + "_title": "Claw", + "_glyph": 148, + "_showGlyph": false, + "Range/Min": -1.0, + "Range/Max": 1.0, + "Range/Center": 0.0, + "Visuals/Num tick marks": 5, + "Visuals/Show text": true, + "Visuals/Orientation": "HORIZONTAL" + }, + { + "_type": "Number Bar", + "_source0": "network_table:///Shuffleboard/Motors/Turret/Applied Output", + "_title": "Turret", + "_glyph": 148, + "_showGlyph": false, + "Range/Min": -1.0, + "Range/Max": 1.0, + "Range/Center": 0.0, + "Visuals/Num tick marks": 5, + "Visuals/Show text": true, + "Visuals/Orientation": "HORIZONTAL" + }, + { + "_type": "Number Bar", + "_source0": "network_table:///Shuffleboard/Motors/Arm/Applied Output", + "_title": "Arm", + "_glyph": 148, + "_showGlyph": false, + "Range/Min": -1.0, + "Range/Max": 1.0, + "Range/Center": 0.0, + "Visuals/Num tick marks": 5, + "Visuals/Show text": true, + "Visuals/Orientation": "HORIZONTAL" + } + ] + } + }, + "8,0": { + "size": [ + 9, + 7 + ], + "content": { + "_type": "Camera Stream", + "_source0": "camera_server://Arm", + "_title": "Arm", + "_glyph": 148, + "_showGlyph": false, + "Crosshair/Show crosshair": true, + "Crosshair/Crosshair color": "#FFFFFFFF", + "Controls/Show controls": true, + "Controls/Rotation": "HALF", + "compression": 1.0, + "fps": 15, + "imageWidth": 640, + "imageHeight": 480 + } + }, + "8,7": { + "size": [ + 9, + 7 + ], + "content": { + "_type": "Camera Stream", + "_source0": "camera_server://limelight", + "_title": "limelight", + "_glyph": 148, + "_showGlyph": false, + "Crosshair/Show crosshair": true, + "Crosshair/Crosshair color": "#FFFFFFFF", + "Controls/Show controls": true, + "Controls/Rotation": "HALF", + "compression": -1.0, + "fps": 22, + "imageWidth": 320, + "imageHeight": 240 + } + }, + "17,0": { + "size": [ + 5, + 14 + ], + "content": { + "_type": "Subsystem Layout", + "_source0": "network_table:///SmartDashboard/Scheduler/Ids", + "_title": "Scheduler", + "_glyph": 149, + "_showGlyph": false, + "Layout/Label position": "BOTTOM", + "_children": [] + } + } + } + } + }, + { + "title": "Tab 3", + "autoPopulate": false, + "autoPopulatePrefix": "", + "widgetPane": { + "gridSize": 32.0, + "showGrid": true, + "hgap": 16.0, + "vgap": 16.0, + "titleType": 0, + "tiles": { + "1,0": { + "size": [ + 1, + 12 + ], + "content": { + "_type": "Subsystem Layout", + "_source0": "network_table:///SmartDashboard/Scheduler/Ids", + "_title": "SmartDashboard/Scheduler/Ids", + "_glyph": 149, + "_showGlyph": false, + "Layout/Label position": "BOTTOM", + "_children": [] + } + } + } + } + } + ], + "windowGeometry": { + "x": -7.199999809265137, + "y": -7.199999809265137, + "width": 1550.4000244140625, + "height": 838.4000244140625 + } +} \ No newline at end of file diff --git a/simgui.json b/simgui.json index e8dbe21..4937c92 100644 --- a/simgui.json +++ b/simgui.json @@ -5,14 +5,15 @@ "header": { "open": true } - }, - "navX-Sensor[0]": { - "header": { - "open": true - } } }, "RoboRIO": { + "6V Rail": { + "open": true + }, + "RoboRIO Input": { + "open": true + }, "window": { "visible": true } @@ -31,6 +32,23 @@ "/Shuffleboard/Motors/Right": "Motor Controller", "/Shuffleboard/PID/Accelerometer": "Gyro", "/Shuffleboard/PID/Gyro": "Gyro", + "/Shuffleboard/Subsystems/Arm": "Subsystem", + "/Shuffleboard/Subsystems/AutoCommand": "Command", + "/Shuffleboard/Subsystems/BalanceCommand": "Command", + "/Shuffleboard/Subsystems/Claw": "Subsystem", + "/Shuffleboard/Subsystems/CloseClawCommand": "Command", + "/Shuffleboard/Subsystems/DecreaseMaxSpeedCommand": "Command", + "/Shuffleboard/Subsystems/DriveCommand": "Command", + "/Shuffleboard/Subsystems/FineDriveCommand": "Command", + "/Shuffleboard/Subsystems/IncreaseMaxSpeedCommand": "Command", + "/Shuffleboard/Subsystems/MoveArmYCommand": "Command", + "/Shuffleboard/Subsystems/PDP": "Subsystem", + "/Shuffleboard/Subsystems/PID": "Subsystem", + "/Shuffleboard/Subsystems/PlaceConeSecondLevelCommand": "Command", + "/Shuffleboard/Subsystems/PlaceGamePieceCommand": "Command", + "/Shuffleboard/Subsystems/SwitchIdleModeCommmand": "Command", + "/Shuffleboard/Subsystems/Tank": "Subsystem", + "/Shuffleboard/Subsystems/Turret": "Subsystem", "/SmartDashboard/Scheduler": "Scheduler" }, "windows": { @@ -48,8 +66,14 @@ }, "NetworkTables": { "transitory": { + "LiveWindow": { + "open": true + }, "Shuffleboard": { "open": true + }, + "SmartDashboard": { + "open": true } } } diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 32b463c..c7d84d3 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -31,9 +31,9 @@ public static final class CanConstants { public static final int kLeftRearMotorPort = 2; public static final int kRightFrontMotorPort = 4; public static final int kRightRearMotorPort = 5; - public static final double kRampRate = 0.1; + public static final double kRampRate = 0; - public static double maxSpeed = 0.8; + public static double maxSpeed = 1; public static final double maxSpeedIncrement = 0.05; public static final String kBaseType = "tank"; @@ -41,7 +41,7 @@ public static final class CanConstants { public static final class OperatorConstants { public static final int kDriverControllerPort = 0; - public static final double Pconstant = 0.00882; + public static final double Pconstant = 0.00635; public static final String m_driveControllerType = "accurateTank"; } diff --git a/src/main/java/frc/robot/Interfaces/CANSparkMax.java b/src/main/java/frc/robot/Interfaces/CANSparkMax.java index 0e23cce..9b37903 100644 --- a/src/main/java/frc/robot/Interfaces/CANSparkMax.java +++ b/src/main/java/frc/robot/Interfaces/CANSparkMax.java @@ -1,5 +1,6 @@ package frc.robot.Interfaces; +import com.revrobotics.REVLibError; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; @@ -253,6 +254,9 @@ public void initSendable(SendableBuilder builder) { // and I don't think it'll work. If I put outside, I'll be able to call it in other places too. builder.addBooleanProperty("Brake Mode", this::isBraking, this::setBrakeMode); builder.addBooleanProperty("Coast Mode", this::isCoasting, this::setCoastMode); + + // current limits + builder.addIntegerProperty("Current Limit", null, this::setSmartCurrentLimit); } /** @@ -311,4 +315,9 @@ public void setCoastMode(boolean coast) { setIdleMode(IdleMode.kBrake); } } + + public REVLibError setSmartCurrentLimit(Long limit) { + throwIfClosed(); + return setSmartCurrentLimit(limit.intValue(), 0, 20000); + } } diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 8c88eb4..84ad454 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -4,6 +4,8 @@ package frc.robot; +import edu.wpi.first.wpilibj.DataLogManager; +import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; @@ -31,6 +33,9 @@ public void robotInit() { m_robotContainer = new RobotContainer(); // Test values for the servo on startup (This is just a test that should be removed if it // actually works) + + DataLogManager.start(); + DriverStation.startDataLog(DataLogManager.getLog()); } /** @@ -58,7 +63,6 @@ public void disabledInit() {} public void disabledPeriodic() {} /** This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */ - @Override public void autonomousInit() { m_autonomousCommand = m_robotContainer.getAutonomousCommand(); diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 4c97300..04a6bc4 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -39,15 +39,13 @@ public class RobotContainer { private final MoveArmYCommand m_MoveArmYCommand = new MoveArmYCommand(m_Arm); private final DriveCommand m_DriveCommand = new DriveCommand(m_Tank); private final BalanceCommand m_BalanceCommand = new BalanceCommand(m_PID, m_Tank); - private final PlaceCubeFirstLevelCommand m_PlaceGamePieceCommand = - new PlaceCubeFirstLevelCommand(m_Tank, m_claw, m_Arm); private final AutoCommand m_AutoCommand = new AutoCommand(m_PID, m_Tank, m_claw, m_Arm); + private final PlaceConeSecondLevelCommand m_PlaceConeSecondLevelCommand = + new PlaceConeSecondLevelCommand(m_Tank, m_Arm); private final IncreaseMaxSpeedCommand m_IncreaseMaxSpeedCommand = new IncreaseMaxSpeedCommand(m_Tank); private final DecreaseMaxSpeedCommand m_DecreaseMaxSpeedCommand = new DecreaseMaxSpeedCommand(m_Tank); - private final SwitchIdleModeCommmand m_SwitchIdleModeCommmand = - new SwitchIdleModeCommmand(m_Tank); private final FineDriveCommand m_FineDriveCommand = new FineDriveCommand(m_Tank); /** The container for the robot. Contains subsystems, OI devices, and commands. */ @@ -57,12 +55,23 @@ public RobotContainer() { // add a few things to the shuffleboard // joysticks - Shuffleboard.getTab("Driver").add("Left Stick Y", m_driverController.getRawAxis(1)); - Shuffleboard.getTab("Driver").add("Right Stick X", m_driverController.getRawAxis(4)); - Shuffleboard.getTab("Driver") - .add("Left Stick Y Adjusted", getDriverControllerLeftStickYAdjusted()); - Shuffleboard.getTab("Driver") - .add("Right Stick X Adjusted", getDriverControllerRightStickXAdjusted()); + var tab = Shuffleboard.getTab("Subsystems"); + tab.add(m_Arm); + tab.add(m_AutoCommand); + tab.add(m_BalanceCommand); + tab.add(m_CloseClawCommand); + tab.add(m_DecreaseMaxSpeedCommand); + tab.add(m_DriveCommand); + tab.add(m_FineDriveCommand); + tab.add(m_IncreaseMaxSpeedCommand); + tab.add(m_MoveArmYCommand); + tab.add(m_PDP); + + tab.add(m_PID); + tab.add(m_PlaceConeSecondLevelCommand); + tab.add(m_Tank); + tab.add(m_Turret); + tab.add(m_claw); } /** @@ -73,23 +82,19 @@ public RobotContainer() { private void configureButtonBindings() { new JoystickButton(m_driverController, XboxController.Button.kY.value) .whileTrue(m_BalanceCommand); - new JoystickButton(m_driverController, XboxController.Button.kA.value) - .whileTrue(m_PlaceGamePieceCommand); - new JoystickButton(m_driverController, XboxController.Button.kStart.value) .whileTrue(m_IncreaseMaxSpeedCommand); new JoystickButton(m_driverController, XboxController.Button.kBack.value) .whileTrue(m_DecreaseMaxSpeedCommand); - new JoystickButton(m_driverController, XboxController.Button.kX.value) - .whileTrue(m_SwitchIdleModeCommmand); - new JoystickButton(m_armController2, XboxController.Button.kLeftBumper.value) + new JoystickButton(m_armController2, XboxController.Button.kX.value) .whileTrue(m_CloseClawCommand); - new JoystickButton(m_armController2, XboxController.Button.kRightBumper.value) + new JoystickButton(m_armController2, XboxController.Button.kY.value) .whileTrue(m_OpenClawCommand); - - new JoystickButton(m_armController2, XboxController.Button.kA.value) + new JoystickButton(m_armController2, XboxController.Button.kLeftBumper.value) .whileTrue(m_FineDriveCommand); + new JoystickButton(m_armController2, XboxController.Button.kB.value) + .whileTrue(m_PlaceConeSecondLevelCommand); } public static double getDriverControllerLeftStickY() { diff --git a/src/main/java/frc/robot/commands/AutoCommand.java b/src/main/java/frc/robot/commands/AutoCommand.java index ec592f4..a74b202 100644 --- a/src/main/java/frc/robot/commands/AutoCommand.java +++ b/src/main/java/frc/robot/commands/AutoCommand.java @@ -7,12 +7,12 @@ import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; import frc.robot.subsystems.*; - public class AutoCommand extends SequentialCommandGroup { public AutoCommand(PID m_pid, Tank m_driveBase, Claw m_claw, Arm m_arm) { - addCommands(new PlaceCubeFirstLevelCommand(m_driveBase, m_claw, m_arm), new BalanceCommand(m_pid, m_driveBase)); - - //new PlaceCubeFirstLevelCommand(m_driveBase, m_claw, m_arm) - //new PlaceConeSecondLevelCommand(m_driveBase, m_arm) + addCommands(new PlaceConeSecondLevelCommand(m_driveBase, m_arm)); + + // new BalanceCommand(m_pid, m_driveBase); + // new PlaceCubeFirstLevelCommand(m_driveBase, m_claw, m_arm) + // new PlaceConeSecondLevelCommand(m_driveBase, m_arm) } } diff --git a/src/main/java/frc/robot/commands/BalanceCommand.java b/src/main/java/frc/robot/commands/BalanceCommand.java index c14b3d5..46e0161 100644 --- a/src/main/java/frc/robot/commands/BalanceCommand.java +++ b/src/main/java/frc/robot/commands/BalanceCommand.java @@ -44,7 +44,7 @@ public void initialize() { // avoid while loops inside execute @Override public void execute() { - double pitchOffset = pid.gyro.getPitch() - initPitch; + double pitchOffset = initPitch - pid.gyro.getPitch(); SmartDashboard.putNumber("pitch offset", pitchOffset); if (pitchOffset > max) { @@ -52,7 +52,7 @@ public void execute() { } SmartDashboard.putNumber("max offset", max); - if (pitchOffset < 17 && !onRamp) { + if (pitchOffset < 16 && !onRamp) { driveBase.setAllMotors(0.5); SmartDashboard.putBoolean("onRamp", onRamp); @@ -63,8 +63,7 @@ public void execute() { if (Math.abs(pitchOffset) < 2) { driveBase.setAllMotors(0); } else { - driveBase.setAllMotors( - Constants.OperatorConstants.Pconstant * (pitchOffset)); + driveBase.setAllMotors(Constants.OperatorConstants.Pconstant * (pitchOffset)); SmartDashboard.putNumber( "motor speed", Constants.OperatorConstants.Pconstant * (pitchOffset)); diff --git a/src/main/java/frc/robot/commands/DriveCommand.java b/src/main/java/frc/robot/commands/DriveCommand.java index a645116..e5093bd 100644 --- a/src/main/java/frc/robot/commands/DriveCommand.java +++ b/src/main/java/frc/robot/commands/DriveCommand.java @@ -27,7 +27,7 @@ public void execute() { // double check getMaxSpeed(), might be wrong m_drivebase.arcadeDrive( RobotContainer.getDriverControllerLeftStickYAdjusted() * Constants.CanConstants.maxSpeed, - RobotContainer.getDriverControllerRightStickXAdjusted() * 0.65); + RobotContainer.getDriverControllerRightStickXAdjusted() * Constants.CanConstants.maxSpeed); SmartDashboard.putNumber("maxSpeed", Constants.CanConstants.maxSpeed); } diff --git a/src/main/java/frc/robot/commands/MoveArmXCommand.java b/src/main/java/frc/robot/commands/MoveArmXCommand.java index 75d0714..2049149 100644 --- a/src/main/java/frc/robot/commands/MoveArmXCommand.java +++ b/src/main/java/frc/robot/commands/MoveArmXCommand.java @@ -22,7 +22,7 @@ public void initialize() {} @Override public void execute() { - m_subsystem.rotateTurret(RobotContainer.getControllerRightStickX()); + m_subsystem.rotateTurret(RobotContainer.getControllerRightStickX() / 1.5); } @Override diff --git a/src/main/java/frc/robot/commands/MoveArmYCommand.java b/src/main/java/frc/robot/commands/MoveArmYCommand.java index cf5c3a4..b1d6b7f 100644 --- a/src/main/java/frc/robot/commands/MoveArmYCommand.java +++ b/src/main/java/frc/robot/commands/MoveArmYCommand.java @@ -22,7 +22,7 @@ public void initialize() {} @Override public void execute() { - m_subsystem.moveArm(RobotContainer.getControllerLeftStickY()); + m_subsystem.moveArm(RobotContainer.getControllerLeftStickY() * 1.5); } @Override diff --git a/src/main/java/frc/robot/commands/PlaceConeSecondLevelCommand.java b/src/main/java/frc/robot/commands/PlaceConeSecondLevelCommand.java index c34201a..06956e9 100644 --- a/src/main/java/frc/robot/commands/PlaceConeSecondLevelCommand.java +++ b/src/main/java/frc/robot/commands/PlaceConeSecondLevelCommand.java @@ -9,11 +9,11 @@ public class PlaceConeSecondLevelCommand extends CommandBase { @SuppressWarnings({"PMD.UnusedPrivateField", "PMD.SingularField"}) - private final Tank drive; + private final Tank drive; + private final Arm arm; - private boolean readyToMoveArmBack = false; - private boolean end = false; + private boolean firstStep = true; public PlaceConeSecondLevelCommand(Tank drive, Arm arm) { this.drive = drive; @@ -32,37 +32,46 @@ public void initialize() { arm.armMotor.getEncoder().setPosition(0); } - - //double check constants + // double check constants @Override public void execute() { - if (Math.abs(arm.armMotor.getEncoder().getPosition()) < 80) { - arm.armMotor.set(0.4); //move the arm until cone gets in - } else { - if(Math.abs(drive.getAverageDistance()) < 10){ - drive.arcadeDrive(-2, 0); //move back so that cone falls in - } else{ - drive.arcadeDrive(0, 0);; //stop moving - readyToMoveArmBack = true; //ready to move the arm back and continue balance + if (firstStep) { + if (Math.abs(arm.armMotor.getEncoder().getPosition()) < 105) { + arm.armMotor.set(0.4); + } + + if (Math.abs(arm.armMotor.getEncoder().getPosition()) >= 105) { + firstStep = false; + arm.armMotor.set(0); arm.armMotor.getEncoder().setPosition(0); } - } - if(readyToMoveArmBack){ - if(Math.abs(arm.armMotor.getEncoder().getPosition()) < 80){ - arm.armMotor.set(-0.4); //moves the arm back to starting position - end = true; + // go over charge station + if (Math.abs(drive.getAverageDistance()) < 4.6 && firstStep == false) { + drive.setAllMotors(-0.3); // move back so that cone falls in + arm.armMotor.set(-0.45); + } + + if (Math.abs(drive.getAverageDistance()) >= 4.6) { + drive.setAllMotors(0); } } } @Override public void end(boolean interrupted) { + drive.leftFront.getEncoder().setPosition(0); + drive.leftRear.getEncoder().setPosition(0); + drive.rightFront.getEncoder().setPosition(0); + drive.rightRear.getEncoder().setPosition(0); + arm.armMotor.getEncoder().setPosition(0); + + drive.setAllMotors(0); arm.armMotor.set(0); // stop the arm motor } @Override public boolean isFinished() { - return end; + return Math.abs(drive.getAverageDistance()) >= 4.6; } } diff --git a/src/main/java/frc/robot/commands/PlaceCubeFirstLevelCommand.java b/src/main/java/frc/robot/commands/PlaceCubeFirstLevelCommand.java deleted file mode 100644 index 3fe07ca..0000000 --- a/src/main/java/frc/robot/commands/PlaceCubeFirstLevelCommand.java +++ /dev/null @@ -1,73 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package frc.robot.commands; - -import edu.wpi.first.wpilibj2.command.CommandBase; -import frc.robot.subsystems.*; - -public class PlaceCubeFirstLevelCommand extends CommandBase { - @SuppressWarnings({"PMD.UnusedPrivateField", "PMD.SingularField"}) - private final Tank drive; - private final Claw claw; - private final Arm arm; - - private boolean readyToMoveArmBack = false; - private boolean end = false; - - public PlaceCubeFirstLevelCommand(Tank drive, Claw claw, Arm arm) { - this.drive = drive; - this.claw = claw; - this.arm = arm; - addRequirements(drive); - addRequirements(claw); - addRequirements(arm); - } - - @Override - public void initialize() { - drive.leftFront.getEncoder().setPosition(0); - drive.leftRear.getEncoder().setPosition(0); - drive.rightFront.getEncoder().setPosition(0); - drive.rightRear.getEncoder().setPosition(0); - - arm.armMotor.getEncoder().setPosition(0); - - claw.clawMotor.getEncoder().setPosition(0); - } - - - //double check constants - @Override - public void execute() { - if (Math.abs(arm.armMotor.getEncoder().getPosition()) < 100) { - arm.armMotor.set(0.4); //move the arm back until it can reach botton - } else { - if(Math.abs(claw.clawMotor.getEncoder().getPosition()) < 20){ - claw.openClaw(); //open claw a little and drops cube - } else{ - claw.stopClaw(); //stop claw - readyToMoveArmBack = true; //ready to move the arm back and continue balance - arm.armMotor.getEncoder().setPosition(0); - } - } - - if(readyToMoveArmBack){ - if(Math.abs(arm.armMotor.getEncoder().getPosition()) < 100){ - arm.armMotor.set(-0.4); //moves the arm back to starting position - end = true; - } - } - } - - @Override - public void end(boolean interrupted) { - arm.armMotor.set(0); // stop the arm motor - } - - @Override - public boolean isFinished() { - return end; - } -} diff --git a/src/main/java/frc/robot/commands/SwitchIdleModeCommmand.java b/src/main/java/frc/robot/commands/SwitchIdleModeCommmand.java deleted file mode 100644 index e201201..0000000 --- a/src/main/java/frc/robot/commands/SwitchIdleModeCommmand.java +++ /dev/null @@ -1,34 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package frc.robot.commands; - -import edu.wpi.first.wpilibj2.command.CommandBase; -import frc.robot.subsystems.Tank; - -public class SwitchIdleModeCommmand extends CommandBase { - @SuppressWarnings({"PMD.UnusedPrivateField", "PMD.SingularField"}) - private final Tank m_subsystem; - - public SwitchIdleModeCommmand(Tank subsystem) { - m_subsystem = subsystem; - addRequirements(subsystem); - } - - @Override - public void initialize() { - m_subsystem.switchIdleMode(); - } - - @Override - public void execute() {} - - @Override - public void end(boolean interrupted) {} - - @Override - public boolean isFinished() { - return false; - } -} diff --git a/src/main/java/frc/robot/subsystems/Arm.java b/src/main/java/frc/robot/subsystems/Arm.java index 0456a8e..c6bc7a8 100644 --- a/src/main/java/frc/robot/subsystems/Arm.java +++ b/src/main/java/frc/robot/subsystems/Arm.java @@ -24,8 +24,9 @@ public class Arm extends SubsystemBase { public Arm() { armMotor = new CANSparkMax(7, MotorType.kBrushless); armMotor.setIdleMode(IdleMode.kBrake); - armMotor.setSmartCurrentLimit(20, 30); + armMotor.setSmartCurrentLimit(10, 40); armMotor.burnFlash(); + addChild("Arm Motor", armMotor); Shuffleboard.getTab("Motors").add("Arm", armMotor); } diff --git a/src/main/java/frc/robot/subsystems/Claw.java b/src/main/java/frc/robot/subsystems/Claw.java index 1b4bb71..cf0cccd 100644 --- a/src/main/java/frc/robot/subsystems/Claw.java +++ b/src/main/java/frc/robot/subsystems/Claw.java @@ -27,8 +27,9 @@ public class Claw extends SubsystemBase { public Claw() { clawMotor = new CANSparkMax(8, MotorType.kBrushless); clawMotor.setIdleMode(IdleMode.kBrake); - clawMotor.setSmartCurrentLimit(18, 11); + clawMotor.setSmartCurrentLimit(20, 11); clawMotor.burnFlash(); + addChild("Claw Motor", clawMotor); Shuffleboard.getTab("Motors").add("Claw", clawMotor); diff --git a/src/main/java/frc/robot/subsystems/PID.java b/src/main/java/frc/robot/subsystems/PID.java index a388fc9..9d9fef9 100644 --- a/src/main/java/frc/robot/subsystems/PID.java +++ b/src/main/java/frc/robot/subsystems/PID.java @@ -4,6 +4,7 @@ import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.wpilibj.SPI; import edu.wpi.first.wpilibj.Timer; +import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.SubsystemBase; @@ -28,9 +29,12 @@ public PID() { toleranceDeg = 0.5; iLimit = 2.0; gyro = new AHRS(SPI.Port.kMXP); + addChild("Gyro", gyro); + Shuffleboard.getTab("Driver").add("Gyro", gyro); initPitch = gyro.getPitch(); pidController = new PIDController(P, I, D); + addChild("PID Controller", pidController); } @Override diff --git a/src/main/java/frc/robot/subsystems/Tank.java b/src/main/java/frc/robot/subsystems/Tank.java index a96d529..731f498 100644 --- a/src/main/java/frc/robot/subsystems/Tank.java +++ b/src/main/java/frc/robot/subsystems/Tank.java @@ -54,6 +54,8 @@ public class Tank extends SubsystemBase { private GenericEntry allWidget; private GenericEntry driveWidget; + + private int initialCurrentLimit = 50; /** */ public Tank() { motorsTab = Shuffleboard.getTab("Motors"); @@ -62,8 +64,8 @@ public Tank() { leftFront.restoreFactoryDefaults(); leftFront.setInverted(true); leftFront.setIdleMode(IdleMode.kBrake); - leftFront.setSmartCurrentLimit(40); - // leftFront.setOpenLoopRampRate(Constants.CanConstants.kRampRate); + leftFront.setSmartCurrentLimit(initialCurrentLimit); + leftFront.setOpenLoopRampRate(Constants.CanConstants.kRampRate); leftFront.burnFlash(); motorsTab.add("Left Front", leftFront); addChild("Left Front", leftFront); @@ -72,8 +74,8 @@ public Tank() { leftRear.restoreFactoryDefaults(); leftRear.setInverted(true); leftRear.setIdleMode(IdleMode.kBrake); - leftRear.setSmartCurrentLimit(40); - // leftRear.setOpenLoopRampRate(Constants.CanConstants.kRampRate); + leftRear.setSmartCurrentLimit(initialCurrentLimit); + leftRear.setOpenLoopRampRate(Constants.CanConstants.kRampRate); leftRear.burnFlash(); motorsTab.add("Left Rear", leftRear); addChild("Left Rear", leftRear); @@ -87,8 +89,8 @@ public Tank() { rightFront.setInverted(false); rightFront.setIdleMode(IdleMode.kBrake); - rightFront.setSmartCurrentLimit(40); - // rightFront.setOpenLoopRampRate(Constants.CanConstants.kRampRate); + rightFront.setSmartCurrentLimit(initialCurrentLimit); + rightFront.setOpenLoopRampRate(Constants.CanConstants.kRampRate); rightFront.burnFlash(); motorsTab.add("Right Front", rightFront); addChild("Right Front", rightFront); @@ -97,8 +99,8 @@ public Tank() { rightRear.restoreFactoryDefaults(); rightRear.setInverted(false); rightRear.setIdleMode(IdleMode.kBrake); - rightRear.setSmartCurrentLimit(40); - // rightRear.setOpenLoopRampRate(Constants.CanConstants.kRampRate); + rightRear.setSmartCurrentLimit(initialCurrentLimit); + rightRear.setOpenLoopRampRate(Constants.CanConstants.kRampRate); rightRear.burnFlash(); motorsTab.add("Right Rear", rightRear); diff --git a/src/main/java/frc/robot/subsystems/Turret.java b/src/main/java/frc/robot/subsystems/Turret.java index 2c868c4..3d22d4a 100644 --- a/src/main/java/frc/robot/subsystems/Turret.java +++ b/src/main/java/frc/robot/subsystems/Turret.java @@ -21,6 +21,7 @@ public Turret() { xMotor.setIdleMode(IdleMode.kBrake); xMotor.setSmartCurrentLimit(5, 10); xMotor.burnFlash(); + addChild("Turret Motor", xMotor); Shuffleboard.getTab("Motors").add("Turret", xMotor); }