Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
57 changes: 57 additions & 0 deletions wpilibcExamples/src/main/cpp/examples/Xrptimed/cpp/Robot.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
// 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.

#include "Robot.h"

Robot::Robot() {
wpi::SendableRegistry::AddChild(&m_drive, &m_leftMotor);
wpi::SendableRegistry::AddChild(&m_drive, &m_rightMotor);

// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
m_rightMotor.SetInverted(true);
}

/**
* This function is called every 20 ms, no matter the mode. Use
* this for items like diagnostics that you want ran during disabled,
* autonomous, teleoperated and test.
*
* <p> This runs after the mode specific periodic functions, but before
* LiveWindow and SmartDashboard integrated updating.
*/
void Robot::RobotPeriodic() {}

// This function is only once each time Autonomous is enabled
void Robot::AutonomousInit() {
m_timer.Restart();
}

// This function is called periodically during autonomous mode
void Robot::AutonomousPeriodic() {
// Drive for 2 seconds
if (m_timer.Get() < 2_s) {
// Drive forwards half speed, make sure to turn input squaring off
m_drive.ArcadeDrive(0.5, 0.0, false);
} else {
// Stop robot
m_drive.ArcadeDrive(0.0, 0.0, false);
}
}

// This function is only once each time telop is enabled
void Robot::TeleopInit() {}

// This function is called periodically during teleop mode
void Robot::TeleopPeriodic() {
m_drive.ArcadeDrive(-m_XboxController.GetLeftY(),
-m_XboxController.GetRightX());
}

#ifndef RUNNING_FRC_TESTS
int main() {
return frc::StartRobot<Robot>();
}
#endif
31 changes: 31 additions & 0 deletions wpilibcExamples/src/main/cpp/examples/Xrptimed/include/Robot.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
// 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.

#pragma once

#include <frc/TimedRobot.h>
#include <frc/Timer.h>
#include <frc/XboxController.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc/xrp/XRPMotor.h>

class Robot : public frc::TimedRobot {
public:
Robot();
void RobotPeriodic() override;
void AutonomousInit() override;
void AutonomousPeriodic() override;
void TeleopInit() override;
void TeleopPeriodic() override;

private:
frc::XRPMotor m_leftMotor{0};
frc::XRPMotor m_rightMotor{1};
frc::XboxController m_XboxController{0};
frc::Timer m_timer;

frc::DifferentialDrive m_drive{
[&](double output) { m_leftMotor.Set(output); },
[&](double output) { m_rightMotor.Set(output); }};
};
16 changes: 16 additions & 0 deletions wpilibcExamples/src/main/cpp/examples/examples.json
Original file line number Diff line number Diff line change
Expand Up @@ -609,6 +609,22 @@
"xrp"
]
},
{
"name": "XRP Timed",
"description": "An very basic timed robot program that can be used with the XRP reference robot design.",
"tags": [
"XRP",
"Differential Drive",
"XboxController"
],
"foldername": "Xrptimed",
"gradlebase": "cppxrp",
"mainclass": "Main",
"commandversion": 2,
"extravendordeps": [
"xrp"
]
},
{
"name": "StateSpaceFlywheel",
"description": "Control a flywheel using a state-space model (based on values from CAD), with a Kalman Filter and LQR.",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -812,6 +812,22 @@
"xrp"
]
},
{
"name": "XRP Timed",
"description": "An very basic timed robot program that can be used with the XRP reference robot design.",
"tags": [
"XRP",
"Differential Drive",
"XboxController"
],
"foldername": "xrptimed",
"gradlebase": "javaxrp",
"mainclass": "Main",
"commandversion": 2,
"extravendordeps": [
"xrp"
]
},
{
"name": "Digital Communication Sample",
"description": "Communicates with external devices (such as an Arduino) using the roboRIO's DIO.",
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
// 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 edu.wpi.first.wpilibj.examples.xrptimed;

import edu.wpi.first.wpilibj.RobotBase;

/**
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
* you are doing, do not modify this file except to change the parameter class to the startRobot
* call.
*/
public final class Main {
private Main() {}

/**
* Main initialization function. Do not perform any initialization here.
*
* <p>If you change your main robot class, change the parameter type.
*/
public static void main(String... args) {
RobotBase.startRobot(Robot::new);
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
// 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 edu.wpi.first.wpilibj.examples.xrptimed;

import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.xrp.XRPMotor;

/**
* The methods in this class are called automatically corresponding to each mode, as described in
* the TimedRobot documentation. If you change the name of this class or the package after creating
* this project, you must also update the manifest file in the resource directory.
*/
public class Robot extends TimedRobot {
private final XRPMotor m_leftDrive = new XRPMotor(0);
private final XRPMotor m_rightDrive = new XRPMotor(1);
private final DifferentialDrive m_robotDrive =
new DifferentialDrive(m_leftDrive::set, m_rightDrive::set);
private final XboxController m_controller = new XboxController(0);
private final Timer m_timer = new Timer();

/** Called once at the beginning of the robot program. */
public Robot() {
SendableRegistry.addChild(m_robotDrive, m_leftDrive);
SendableRegistry.addChild(m_robotDrive, m_rightDrive);

// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
m_rightDrive.setInverted(true);
}

/** This function is run once each time the robot enters autonomous mode. */
@Override
public void autonomousInit() {
m_timer.restart();
}

/** This function is called periodically during autonomous. */
@Override
public void autonomousPeriodic() {
// Drive for 2 seconds
if (m_timer.get() < 2.0) {
// Drive forwards half speed, make sure to turn input squaring off
m_robotDrive.arcadeDrive(0.5, 0.0, false);
} else {
m_robotDrive.stopMotor(); // stop robot
}
}

/** This function is called once each time the robot enters teleoperated mode. */
@Override
public void teleopInit() {}

/** This function is called periodically during teleoperated mode. */
@Override
public void teleopPeriodic() {
m_robotDrive.arcadeDrive(-m_controller.getLeftY(), -m_controller.getRightX());
}

/** This function is called once each time the robot enters test mode. */
@Override
public void testInit() {}

/** This function is called periodically during test mode. */
@Override
public void testPeriodic() {}
}
Loading