Initial commit of the WPILib simulation support in an alpha quality state.

Fixes to deal with the switch to .hpp files in the HAL and other misc problems due to rebasing.

Added Omar's changes to the compressor interface

Fixes to make C++ plugin compile on linux.

Added import of the WPILibSim code from the graduate class. It shows up as wpilibJavaSim to follow the convention set by wpilibJava, wpilibJavaJNI and wpilibJavaFinal.

Fixed wpilibJavaSim artifactId to mirror the new convention.

Modified the build of the java plugin to pull in the simulation dependencies.

Added stacktrace printing.

Fixed support for creating projects.

Added support for the isReal() and isSimulation() methods along with the AnalogPotentiometer object to support simulating GearsBot.

Added support for a "WPILib Simulate" button.

Added GearsBot to the built in examples.

Added support for specifying the world file during project creation and switched the default from BluntObjectBot to GearsBot.

Removed unused import.

Added file browser for world files.

Added support for debugging in simulation.

Change simulate icon to be a Gazebo icon.

Switched over to the gazebo messaging system.

Updated location of default world file.

Reverted cmake change.

Fixed bug in WPILibJSim, added better logging and cleaned up code.

Made the frc_gazebo_plugin build using raw cmake instead of catkin, breaking the final ROS dependencies.

Added installation to frc_gazebo_plugin Makefile.

Fixed running of simulation to actually use frcsim.

Initial commit of simulation library for C++. Has the minimal subset of features necessary for having a Simple Robot run in teleoperated mode.

Added notes for generating protobuf messages.

Import of the debuild process into the main repository.

Moved frc_gazebo_plugin under simulation and removed the gazebo folder.

Updated the gazebo plugin to remove excessive printing and limit motor signal to [-1,1].

Updated WPILibJSim to support latching messages and to sleep for 20ms in iterative robot.

Reduced delay between starting frcsim and the users program to 1 second.

Updated GearsBot example.

Fixed a few minor issues for demoable state.

Added simulator support for Victors, Jaguars and Talons.

Added NetworkTables, SmartDashboard and LiveWindow to the simulator.

Added AnalogPotentiometer for simulation.

Added support for simulating encoders.

Added simulation support for Gyro.

Added IterativeRobot, Fixed Timers, Notifiers, PIDControllers and other minor fixes + cleanup.

Added RobotDrive support to simulation.

Separated out JavaGazebo so that SimDS will be able to reuse it.

Separated out SimDS into its own application..

Fixes so that the SimDS is distributed and runs properly for Java with the eclipse plugins.

Added DriverStation support to WPILibCSim

Cleanup of DriverStation, WaitUntilCommand and AnalogPotentiometer for WPILibCSim.

Cleanup of includes for WPILibCSim

Added AnalogPotentiometer to the real WPILibC.

Added AnalogPotentiometer to the real WPILibC.

Added GearsBot example to C++ eclipse plugin.

WPILibCSim fixes to work with launching from the plugin.

Package libwpilibsim in a deb file.

Added includes to plugin distribution.

Added support for external-limit-switches to Gazebo, Java and C++.

Added support for Gazebo Rangefinders and Analog channels to read their values in C++ and Java.

Added support for internal limit switches.

Updated GearsBot programs to use limit switches + range finders.

Added disabling of motors when robot is disabled to more closely mimic the real robot.

Fixes to deal with the switch to .hpp files in the HAL and other misc problems due to rebasing.

Change-Id: I624c5f4d0f28282616a7c92083575bf68adcdce2
This commit is contained in:
Alex Henning
2014-06-12 11:02:26 -07:00
committed by thomasclark
parent d5a509c7e7
commit cb56c9a144
425 changed files with 38450 additions and 335 deletions

View File

@@ -0,0 +1,22 @@
#include "Autonomous.h"
#include "PrepareToPickup.h"
#include "Pickup.h"
#include "Place.h"
#include "SetDistanceToBox.h"
#include "DriveStraight.h"
#include "SetWristSetpoint.h"
#include "CloseClaw.h"
#include <iostream>
Autonomous::Autonomous() : CommandGroup("Autonomous") {
AddSequential(new PrepareToPickup());
AddSequential(new Pickup());
AddSequential(new SetDistanceToBox(0.10));
// AddSequential(new DriveStraight(4)); // Use Encoders if ultrasonic is broken
AddSequential(new Place());
AddSequential(new SetDistanceToBox(0.60));
// addSequential(new DriveStraight(-2)); // Use Encoders if ultrasonic is broken
AddParallel(new SetWristSetpoint(-45));
AddSequential(new CloseClaw());
}

View File

@@ -0,0 +1,15 @@
#ifndef Autonomous_H
#define Autonomous_H
#include "Commands/CommandGroup.h"
/**
* The main autonomous command to pickup and deliver the
* soda to the box.
*/
class Autonomous: public CommandGroup {
public:
Autonomous();
};
#endif

View File

@@ -0,0 +1,34 @@
#include "CloseClaw.h"
#include "Robot.h"
CloseClaw::CloseClaw() : Command("CloseClaw") {
Requires(Robot::claw);
}
// Called just before this Command runs the first time
void CloseClaw::Initialize() {
Robot::claw->Close();
}
// Called repeatedly when this Command is scheduled to run
void CloseClaw::Execute() {}
// Make this return true when this Command no longer needs to run execute()
bool CloseClaw::IsFinished() {
return Robot::claw->IsGripping() ;
}
// Called once after isFinished returns true
void CloseClaw::End() {
// NOTE: Doesn't stop in simulation due to lower friction causing the can to fall out
// + there is no need to worry about stalling the motor or crushing the can.
#ifdef REAL
Robot::claw->Stop();
#endif
}
// Called when another command which requires one or more of the same
// subsystems is scheduled to run
void CloseClaw::Interrupted() {
End();
}

View File

@@ -0,0 +1,20 @@
#ifndef CloseClaw_H
#define CloseClaw_H
#include "Commands/Command.h"
/**
* Opens the claw for one second. Real robots should use sensors, stalling
* motors is BAD!
*/
class CloseClaw: public Command {
public:
CloseClaw();
void Initialize();
void Execute();
bool IsFinished();
void End();
void Interrupted();
};
#endif

View File

@@ -0,0 +1,50 @@
#include "DriveStraight.h"
#include "Robot.h"
DriveStraight::DriveStraight(double distance) {
Requires(Robot::drivetrain);
pid = new PIDController(4, 0, 0, new DriveStraightPIDSource(),
new DriveStraightPIDOutput());
pid->SetAbsoluteTolerance(0.01);
pid->SetSetpoint(distance);
}
// Called just before this Command runs the first time
void DriveStraight::Initialize() {
// Get everything in a safe starting state.
Robot::drivetrain->Reset();
pid->Reset();
pid->Enable();
}
// Called repeatedly when this Command is scheduled to run
void DriveStraight::Execute() {}
// Make this return true when this Command no longer needs to run execute()
bool DriveStraight::IsFinished() {
return pid->OnTarget();
}
// Called once after isFinished returns true
void DriveStraight::End() {
// Stop PID and the wheels
pid->Disable();
Robot::drivetrain->Drive(0, 0);
}
// Called when another command which requires one or more of the same
// subsystems is scheduled to run
void DriveStraight::Interrupted() {
End();
}
DriveStraightPIDSource::~DriveStraightPIDSource() {}
double DriveStraightPIDSource::PIDGet() {
return Robot::drivetrain->GetDistance();
}
DriveStraightPIDOutput::~DriveStraightPIDOutput() {}
void DriveStraightPIDOutput::PIDWrite(float d) {
Robot::drivetrain->Drive(d, d);
}

View File

@@ -0,0 +1,37 @@
#ifndef DriveStraight_H
#define DriveStraight_H
#include "WPILib.h"
#include "Commands/Command.h"
/**
* Drive the given distance straight (negative values go backwards).
* Uses a local PID controller to run a simple PID loop that is only
* enabled while this command is running. The input is the averaged
* values of the left and right encoders.
*/
class DriveStraight: public Command {
public:
DriveStraight(double distance);
void Initialize();
void Execute();
bool IsFinished();
void End();
void Interrupted();
private:
PIDController* pid;
};
class DriveStraightPIDSource: public PIDSource {
public:
virtual ~DriveStraightPIDSource();
double PIDGet();
};
class DriveStraightPIDOutput: public PIDOutput {
public:
virtual ~DriveStraightPIDOutput();
void PIDWrite(float d);
};
#endif

View File

@@ -0,0 +1,31 @@
#include "OpenClaw.h"
#include "Robot.h"
OpenClaw::OpenClaw() : Command("OpenClaw") {
Requires(Robot::claw);
SetTimeout(1);
}
// Called just before this Command runs the first time
void OpenClaw::Initialize() {
Robot::claw->Open();
}
// Called repeatedly when this Command is scheduled to run
void OpenClaw::Execute() {}
// Make this return true when this Command no longer needs to run execute()
bool OpenClaw::IsFinished() {
return IsTimedOut();
}
// Called once after isFinished returns true
void OpenClaw::End() {
Robot::claw->Stop();
}
// Called when another command which requires one or more of the same
// subsystems is scheduled to run
void OpenClaw::Interrupted() {
End();
}

View File

@@ -0,0 +1,20 @@
#ifndef OpenClaw_H
#define OpenClaw_H
#include "Commands/Command.h"
/**
* Opens the claw for one second. Real robots should use sensors, stalling
* motors is BAD!
*/
class OpenClaw: public Command {
public:
OpenClaw();
void Initialize();
void Execute();
bool IsFinished();
void End();
void Interrupted();
};
#endif

View File

@@ -0,0 +1,12 @@
#include "Pickup.h"
#include "CloseClaw.h"
#include "SetWristSetpoint.h"
#include "SetElevatorSetpoint.h"
#include <iostream>
Pickup::Pickup() : CommandGroup("Pickup") {
AddSequential(new CloseClaw());
AddParallel(new SetWristSetpoint(-45));
AddSequential(new SetElevatorSetpoint(0.25));
}

View File

@@ -0,0 +1,15 @@
#ifndef Pickup_H
#define Pickup_H
#include "Commands/CommandGroup.h"
/**
* Pickup a soda can (if one is between the open claws) and
* get it in a safe state to drive around.
*/
class Pickup: public CommandGroup {
public:
Pickup();
};
#endif

View File

@@ -0,0 +1,12 @@
#include "Place.h"
#include "OpenClaw.h"
#include "SetWristSetpoint.h"
#include "SetElevatorSetpoint.h"
#include <iostream>
Place::Place() : CommandGroup("Place") {
AddSequential(new SetElevatorSetpoint(0.25));
AddSequential(new SetWristSetpoint(0));
AddSequential(new OpenClaw());
}

View File

@@ -0,0 +1,14 @@
#ifndef Place_H
#define Place_H
#include "Commands/CommandGroup.h"
/**
* Place a held soda can onto the platform.
*/
class Place: public CommandGroup {
public:
Place();
};
#endif

View File

@@ -0,0 +1,12 @@
#include "PrepareToPickup.h"
#include "OpenClaw.h"
#include "SetWristSetpoint.h"
#include "SetElevatorSetpoint.h"
#include <iostream>
PrepareToPickup::PrepareToPickup() : CommandGroup("PrepareToPickup") {
AddParallel(new OpenClaw());
AddParallel(new SetWristSetpoint(0));
AddSequential(new SetElevatorSetpoint(0));
}

View File

@@ -0,0 +1,14 @@
#ifndef PrepareToPickup_H
#define PrepareToPickup_H
#include "Commands/CommandGroup.h"
/**
* Make sure the robot is in a state to pickup soda cans.
*/
class PrepareToPickup: public CommandGroup {
public:
PrepareToPickup();
};
#endif

View File

@@ -0,0 +1,50 @@
#include "SetDistanceToBox.h"
#include "Robot.h"
SetDistanceToBox::SetDistanceToBox(double distance) {
Requires(Robot::drivetrain);
pid = new PIDController(-2, 0, 0, new SetDistanceToBoxPIDSource(),
new SetDistanceToBoxPIDOutput());
pid->SetAbsoluteTolerance(0.01);
pid->SetSetpoint(distance);
}
// Called just before this Command runs the first time
void SetDistanceToBox::Initialize() {
// Get everything in a safe starting state.
Robot::drivetrain->Reset();
pid->Reset();
pid->Enable();
}
// Called repeatedly when this Command is scheduled to run
void SetDistanceToBox::Execute() {}
// Make this return true when this Command no longer needs to run execute()
bool SetDistanceToBox::IsFinished() {
return pid->OnTarget();
}
// Called once after isFinished returns true
void SetDistanceToBox::End() {
// Stop PID and the wheels
pid->Disable();
Robot::drivetrain->Drive(0, 0);
}
// Called when another command which requires one or more of the same
// subsystems is scheduled to run
void SetDistanceToBox::Interrupted() {
End();
}
SetDistanceToBoxPIDSource::~SetDistanceToBoxPIDSource() {}
double SetDistanceToBoxPIDSource::PIDGet() {
return Robot::drivetrain->GetDistanceToObstacle();
}
SetDistanceToBoxPIDOutput::~SetDistanceToBoxPIDOutput() {}
void SetDistanceToBoxPIDOutput::PIDWrite(float d) {
Robot::drivetrain->Drive(d, d);
}

View File

@@ -0,0 +1,37 @@
#ifndef SetDistanceToBox_H
#define SetDistanceToBox_H
#include "WPILib.h"
#include "Commands/Command.h"
/**
* Drive until the robot is the given distance away from the box. Uses a local
* PID controller to run a simple PID loop that is only enabled while this
* command is running. The input is the averaged values of the left and right
* encoders.
*/
class SetDistanceToBox: public Command {
public:
SetDistanceToBox(double distance);
void Initialize();
void Execute();
bool IsFinished();
void End();
void Interrupted();
private:
PIDController* pid;
};
class SetDistanceToBoxPIDSource: public PIDSource {
public:
virtual ~SetDistanceToBoxPIDSource();
double PIDGet();
};
class SetDistanceToBoxPIDOutput: public PIDOutput {
public:
virtual ~SetDistanceToBoxPIDOutput();
void PIDWrite(float d);
};
#endif

View File

@@ -0,0 +1,29 @@
#include "SetElevatorSetpoint.h"
#include "Robot.h"
#include <math.h>
SetElevatorSetpoint::SetElevatorSetpoint(double setpoint) : Command("SetElevatorSetpoint") {
this->setpoint = setpoint;
Requires(Robot::elevator);
}
// Called just before this Command runs the first time
void SetElevatorSetpoint::Initialize() {
Robot::elevator->SetSetpoint(setpoint);
Robot::elevator->Enable();
}
// Called repeatedly when this Command is scheduled to run
void SetElevatorSetpoint::Execute() {}
// Make this return true when this Command no longer needs to run execute()
bool SetElevatorSetpoint::IsFinished() {
return Robot::elevator->OnTarget();
}
// Called once after isFinished returns true
void SetElevatorSetpoint::End() {}
// Called when another command which requires one or more of the same
// subsystems is scheduled to run
void SetElevatorSetpoint::Interrupted() {}

View File

@@ -0,0 +1,23 @@
#ifndef SetElevatorSetpoint_H
#define SetElevatorSetpoint_H
#include "Commands/Command.h"
/**
* Move the elevator to a given location. This command finishes when it is within
* the tolerance, but leaves the PID loop running to maintain the position. Other
* commands using the elevator should make sure they disable PID!
*/
class SetElevatorSetpoint: public Command {
private:
double setpoint;
public:
SetElevatorSetpoint(double setpoint);
void Initialize();
void Execute();
bool IsFinished();
void End();
void Interrupted();
};
#endif

View File

@@ -0,0 +1,28 @@
#include "SetWristSetpoint.h"
#include "Robot.h"
SetWristSetpoint::SetWristSetpoint(double setpoint) : Command("SetWristSetpoint") {
this->setpoint = setpoint;
Requires(Robot::wrist);
}
// Called just before this Command runs the first time
void SetWristSetpoint::Initialize() {
Robot::wrist->SetSetpoint(setpoint);
Robot::wrist->Enable();
}
// Called repeatedly when this Command is scheduled to run
void SetWristSetpoint::Execute() {}
// Make this return true when this Command no longer needs to run execute()
bool SetWristSetpoint::IsFinished() {
return Robot::wrist->OnTarget();
}
// Called once after isFinished returns true
void SetWristSetpoint::End() {}
// Called when another command which requires one or more of the same
// subsystems is scheduled to run
void SetWristSetpoint::Interrupted() {}

View File

@@ -0,0 +1,23 @@
#ifndef SetWristSetpoint_H
#define SetWristSetpoint_H
#include "Commands/Command.h"
/**
* Move the wrist to a given angle. This command finishes when it is within
* the tolerance, but leaves the PID loop running to maintain the position.
* Other commands using the wrist should make sure they disable PID!
*/
class SetWristSetpoint: public Command {
private:
double setpoint;
public:
SetWristSetpoint(double setpoint);
void Initialize();
void Execute();
bool IsFinished();
void End();
void Interrupted();
};
#endif

View File

@@ -0,0 +1,30 @@
#include "TankDriveWithJoystick.h"
#include "Robot.h"
TankDriveWithJoystick::TankDriveWithJoystick() : Command("TankDriveWithJoystick") {
Requires(Robot::drivetrain);
}
// Called just before this Command runs the first time
void TankDriveWithJoystick::Initialize() {}
// Called repeatedly when this Command is scheduled to run
void TankDriveWithJoystick::Execute() {
Robot::drivetrain->Drive(Robot::oi->GetJoystick());
}
// Make this return true when this Command no longer needs to run execute()
bool TankDriveWithJoystick::IsFinished() {
return false;
}
// Called once after isFinished returns true
void TankDriveWithJoystick::End() {
Robot::drivetrain->Drive(0, 0);
}
// Called when another command which requires one or more of the same
// subsystems is scheduled to run
void TankDriveWithJoystick::Interrupted() {
End();
}

View File

@@ -0,0 +1,19 @@
#ifndef TankDriveWithJoystick_H
#define TankDriveWithJoystick_H
#include "Commands/Command.h"
/**
* Have the robot drive tank style using the PS3 Joystick until interrupted.
*/
class TankDriveWithJoystick: public Command {
public:
TankDriveWithJoystick();
void Initialize();
void Execute();
bool IsFinished();
void End();
void Interrupted();
};
#endif

View File

@@ -0,0 +1,50 @@
/*
* OI.cpp
*
* Created on: Jun 3, 2014
* Author: alex
*/
#include "OI.h"
#include "Commands/SetElevatorSetpoint.h"
#include "Commands/OpenClaw.h"
#include "Commands/CloseClaw.h"
#include "Commands/PrepareToPickup.h"
#include "Commands/Pickup.h"
#include "Commands/Place.h"
#include "Commands/Autonomous.h"
OI::OI() {
SmartDashboard::PutData("Open Claw", new OpenClaw());
SmartDashboard::PutData("Close Claw", new CloseClaw());
joy= new Joystick(1);
// Create some buttons
JoystickButton* d_up = new JoystickButton(joy, 5);
JoystickButton* d_right= new JoystickButton(joy, 6);
JoystickButton* d_down= new JoystickButton(joy, 7);
JoystickButton* d_left = new JoystickButton(joy, 8);
JoystickButton* l2 = new JoystickButton(joy, 9);
JoystickButton* r2 = new JoystickButton(joy, 10);
JoystickButton* l1 = new JoystickButton(joy, 11);
JoystickButton* r1 = new JoystickButton(joy, 12);
// Connect the buttons to commands
d_up->WhenPressed(new SetElevatorSetpoint(0.2));
d_down->WhenPressed(new SetElevatorSetpoint(-0.2));
d_right->WhenPressed(new CloseClaw());
d_left->WhenPressed(new OpenClaw());
r1->WhenPressed(new PrepareToPickup());
r2->WhenPressed(new Pickup());
l1->WhenPressed(new Place());
l2->WhenPressed(new Autonomous());
}
Joystick* OI::GetJoystick() {
return joy;
}

View File

@@ -0,0 +1,22 @@
/*
* OI.h
*
* Created on: Jun 3, 2014
* Author: alex
*/
#ifndef OI_H_
#define OI_H_
#include "WPILib.h"
class OI {
public:
OI();
Joystick* GetJoystick();
private:
Joystick* joy;
};
#endif /* OI_H_ */

View File

@@ -0,0 +1,56 @@
#include "Robot.h"
#include "Commands/Autonomous.h"
DriveTrain* Robot::drivetrain = NULL;
Elevator* Robot::elevator = NULL;
Wrist* Robot::wrist = NULL;
Claw* Robot::claw = NULL;
OI* Robot::oi = NULL;
void Robot::RobotInit() {
drivetrain = new DriveTrain();
elevator = new Elevator();
wrist = new Wrist();
claw = new Claw();
oi = new OI();
autonomousCommand = new Autonomous();
lw = LiveWindow::GetInstance();
// Show what command your subsystem is running on the SmartDashboard
SmartDashboard::PutData(drivetrain);
SmartDashboard::PutData(elevator);
SmartDashboard::PutData(wrist);
SmartDashboard::PutData(claw);
}
void Robot::AutonomousInit() {
autonomousCommand->Start();
std::cout << "Starting Auto" << std::endl;
}
void Robot::AutonomousPeriodic() {
Scheduler::GetInstance()->Run();
}
void Robot::TeleopInit() {
// This makes sure that the autonomous stops running when
// teleop starts running. If you want the autonomous to
// continue until interrupted by another command, remove
// this line or comment it out.
autonomousCommand->Cancel();
std::cout << "Starting Teleop" << std::endl;
}
void Robot::TeleopPeriodic() {
Scheduler::GetInstance()->Run();
}
void Robot::TestPeriodic() {
lw->Run();
}
START_ROBOT_CLASS(Robot);

View File

@@ -0,0 +1,41 @@
/*
* Robot.h
*
* Created on: Jun 3, 2014
* Author: alex
*/
#ifndef MY_ROBOT_H_
#define MY_ROBOT_H_
#include "WPILib.h"
#include "Commands/Command.h"
#include "Subsystems/DriveTrain.h"
#include "Subsystems/Elevator.h"
#include "Subsystems/Wrist.h"
#include "Subsystems/Claw.h"
#include "OI.h"
class Robot: public IterativeRobot {
public:
static DriveTrain* drivetrain;
static Elevator* elevator;
static Wrist* wrist;
static Claw* claw;
static OI* oi;
private:
Command *autonomousCommand;
LiveWindow *lw;
void RobotInit();
void AutonomousInit();
void AutonomousPeriodic();
void TeleopInit();
void TeleopPeriodic();
void TestPeriodic();
};
#endif /* ROBOT_H_ */

View File

@@ -0,0 +1,31 @@
#include "Subsystems/Claw.h"
Claw::Claw() : Subsystem("Claw") {
motor = new Victor(7);
contact = new DigitalInput(5);
// Let's show everything on the LiveWindow
// TODO: LiveWindow::GetInstance()->AddActuator("Claw", "Motor", (Victor) motor);
// TODO: contact
}
void Claw::Open()
{
motor->Set(-1);
}
void Claw::Close()
{
motor->Set(1);
}
void Claw::Stop() {
motor->Set(0);
}
bool Claw::IsGripping() {
return contact->Get();
}

View File

@@ -0,0 +1,45 @@
#ifndef Claw_H
#define Claw_H
#include "Commands/Subsystem.h"
#include "WPILib.h"
/**
* The claw subsystem is a simple system with a motor for opening and closing.
* If using stronger motors, you should probably use a sensor so that the
* motors don't stall.
*/
class Claw: public Subsystem {
private:
SpeedController* motor;
DigitalInput* contact;
public:
Claw();
void InitDefaultCommand() {}
/**
* Set the claw motor to move in the open direction.
*/
void Open();
/**
* Set the claw motor to move in the close direction.
*/
void Close();
/**
* Stops the claw motor from moving.
*/
void Stop();
/**
* Return true when the robot is grabbing an object hard enough
* to trigger the limit switch.
*/
bool IsGripping();
void Log() {}
};
#endif

View File

@@ -0,0 +1,90 @@
#include "DriveTrain.h"
#include "Commands/TankDriveWithJoystick.h"
DriveTrain::DriveTrain() : Subsystem("DriveTrain") {
front_left_motor = new Talon(1);
back_left_motor = new Talon(2);
front_right_motor = new Talon(3);
back_right_motor = new Talon(4);
drive = new RobotDrive(front_left_motor, back_left_motor,
front_right_motor, back_right_motor);
left_encoder = new Encoder(1, 2);
right_encoder = new Encoder(3, 4);
// Encoders may measure differently in the real world and in
// simulation. In this example the robot moves 0.042 barleycorns
// per tick in the real world, but the simulated encoders
// simulate 360 tick encoders. This if statement allows for the
// real robot to handle this difference in devices.
#ifdef REAL
left_encoder->SetDistancePerPulse(0.042);
right_encoder->SetDistancePerPulse(0.042);
#else
// Circumference in ft = 4in/12(in/ft)*PI
left_encoder->SetDistancePerPulse((double) (4.0/12.0*M_PI) / 360.0);
right_encoder->SetDistancePerPulse((double) (4.0/12.0*M_PI) / 360.0);
#endif
left_encoder->Start();
right_encoder->Start();
rangefinder = new AnalogChannel(6);
gyro = new Gyro(1);
// Let's show everything on the LiveWindow
// TODO: LiveWindow::GetInstance()->AddActuator("Drive Train", "Front_Left Motor", (Talon) front_left_motor);
// TODO: LiveWindow::GetInstance()->AddActuator("Drive Train", "Back Left Motor", (Talon) back_left_motor);
// TODO: LiveWindow::GetInstance()->AddActuator("Drive Train", "Front Right Motor", (Talon) front_right_motor);
// TODO: LiveWindow::GetInstance()->AddActuator("Drive Train", "Back Right Motor", (Talon) back_right_motor);
LiveWindow::GetInstance()->AddSensor("Drive Train", "Left Encoder", left_encoder);
LiveWindow::GetInstance()->AddSensor("Drive Train", "Right Encoder", right_encoder);
LiveWindow::GetInstance()->AddSensor("Drive Train", "Rangefinder", rangefinder);
LiveWindow::GetInstance()->AddSensor("Drive Train", "Gyro", gyro);
}
/**
* When no other command is running let the operator drive around
* using the PS3 joystick.
*/
void DriveTrain::InitDefaultCommand() {
SetDefaultCommand(new TankDriveWithJoystick());
}
/**
* The log method puts interesting information to the SmartDashboard.
*/
void DriveTrain::Log() {
SmartDashboard::PutNumber("Left Distance", left_encoder->GetDistance());
SmartDashboard::PutNumber("Right Distance", right_encoder->GetDistance());
SmartDashboard::PutNumber("Left Speed", left_encoder->GetRate());
SmartDashboard::PutNumber("Right Speed", right_encoder->GetRate());
SmartDashboard::PutNumber("Gyro", gyro->GetAngle());
}
void DriveTrain::Drive(double left, double right) {
drive->TankDrive(left, right);
}
void DriveTrain::Drive(Joystick* joy) {
Drive(-joy->GetY(), -joy->GetRawAxis(4));
}
double DriveTrain::GetHeading() {
return gyro->GetAngle();
}
void DriveTrain::Reset() {
gyro->Reset();
left_encoder->Reset();
right_encoder->Reset();
}
double DriveTrain::GetDistance() {
return (left_encoder->GetDistance() + right_encoder->GetDistance())/2;
}
double DriveTrain::GetDistanceToObstacle() {
// Really meters in simulation since it's a rangefinder...
return rangefinder->GetAverageVoltage();
}

View File

@@ -0,0 +1,68 @@
#ifndef DriveTrain_H
#define DriveTrain_H
#include "Commands/Subsystem.h"
#include "WPILib.h"
/**
* The DriveTrain subsystem incorporates the sensors and actuators attached to
* the robots chassis. These include four drive motors, a left and right encoder
* and a gyro.
*/
class DriveTrain : public Subsystem {
private:
SpeedController *front_left_motor, *back_left_motor,
*front_right_motor, *back_right_motor;
RobotDrive* drive;
Encoder *left_encoder, *right_encoder;
AnalogChannel* rangefinder;
Gyro* gyro;
public:
DriveTrain();
/**
* When no other command is running let the operator drive around
* using the PS3 joystick.
*/
void InitDefaultCommand();
/**
* The log method puts interesting information to the SmartDashboard.
*/
void Log();
/**
* Tank style driving for the DriveTrain.
* @param left Speed in range [-1,1]
* @param right Speed in range [-1,1]
*/
void Drive(double left, double right);
/**
* @param joy The ps3 style joystick to use to drive tank style.
*/
void Drive(Joystick* joy);
/**
* @return The robots heading in degrees.
*/
double GetHeading();
/**
* Reset the robots sensors to the zero states.
*/
void Reset();
/**
* @return The distance driven (average of left and right encoders).
*/
double GetDistance();
/**
* @return The distance to the obstacle detected by the rangefinder.
*/
double GetDistanceToObstacle();
};
#endif

View File

@@ -0,0 +1,36 @@
#include "Elevator.h"
#include "SmartDashboard/SmartDashboard.h"
#include "LiveWindow/LiveWindow.h"
Elevator::Elevator() : PIDSubsystem("Elevator", kP_real, kI_real, 0.0) {
#ifdef SIMULATION // Check for simulation and update PID values
GetPIDController()->SetPID(kP_simulation, kI_simulation, 0, 0);
#endif
SetAbsoluteTolerance(0.005);
motor = new Victor(5);
// Conversion value of potentiometer varies between the real world and simulation
#ifdef REAL
pot = new AnalogPotentiometer(2, -2.0/5);
#else
pot = new AnalogPotentiometer(2); // Defaults to meters
#endif
// Let's show everything on the LiveWindow
// TODO: LiveWindow::GetInstance()->AddActuator("Elevator", "Motor", (Victor) motor);
// TODO: LiveWindow::GetInstance()->AddSensor("Elevator", "Pot", (AnalogPotentiometer) pot);
LiveWindow::GetInstance()->AddActuator("Elevator", "PID", GetPIDController());
}
void Elevator::Log() {
// TODO: SmartDashboard::PutData("Wrist Pot", (AnalogPotentiometer) pot);
}
double Elevator::ReturnPIDInput() {
return pot->Get();
}
void Elevator::UsePIDOutput(double d) {
motor->Set(d);
}

View File

@@ -0,0 +1,42 @@
#ifndef Elevator_H
#define Elevator_H
#include "Commands/PIDSubsystem.h"
#include "WPILib.h"
/**
* The elevator subsystem uses PID to go to a given height. Unfortunately, in it's current
* state PID values for simulation are different than in the real world do to minor differences.
*/
class Elevator : public PIDSubsystem {
private:
SpeedController* motor;
Potentiometer* pot;
static const double kP_real = 4, kI_real = 0.07,
kP_simulation = 18, kI_simulation = 0.2;
public:
Elevator();
void InitDefaultCommand() {}
/**
* The log method puts interesting information to the SmartDashboard.
*/
void Log();
/**
* Use the potentiometer as the PID sensor. This method is automatically
* called by the subsystem.
*/
double ReturnPIDInput();
/**
* Use the motor as the PID output. This method is automatically called by
* the subsystem.
*/
void UsePIDOutput(double d);
};
#endif

View File

@@ -0,0 +1,36 @@
#include "Wrist.h"
#include "SmartDashboard/SmartDashboard.h"
#include "LiveWindow/LiveWindow.h"
Wrist::Wrist() : PIDSubsystem("Wrist", kP_real, 0.0, 0.0) {
#ifdef SIMULATION // Check for simulation and update PID values
GetPIDController()->SetPID(kP_simulation, 0, 0, 0);
#endif
SetAbsoluteTolerance(2.5);
motor = new Victor(6);
// Conversion value of potentiometer varies between the real world and simulation
#ifdef REAL
pot = new AnalogPotentiometer(3, -270.0/5);
#else
pot = new AnalogPotentiometer(3); // Defaults to degrees
#endif
// Let's show everything on the LiveWindow
// TODO: LiveWindow::GetInstance()->AddActuator("Wrist", "Motor", (Victor) motor);
// TODO: LiveWindow::GetInstance()->AddSensor("Wrist", "Pot", (AnalogPotentiometer) pot);
LiveWindow::GetInstance()->AddActuator("Wrist", "PID", GetPIDController());
}
void Wrist::Log() {
// TODO: SmartDashboard::PutData("Wrist Angle", (AnalogPotentiometer) pot);
}
double Wrist::ReturnPIDInput() {
return pot->Get();
}
void Wrist::UsePIDOutput(double d) {
motor->Set(d);
}

View File

@@ -0,0 +1,40 @@
#ifndef Wrist_H
#define Wrist_H
#include "Commands/PIDSubsystem.h"
#include "WPILib.h"
/**
* The wrist subsystem is like the elevator, but with a rotational joint instead
* of a linear joint.
*/
class Wrist : public PIDSubsystem {
private:
SpeedController* motor;
Potentiometer* pot; // TODO: Make Potentiometer
static const double kP_real = 1, kP_simulation = 0.05;
public:
Wrist();
void InitDefaultCommand() {}
/**
* The log method puts interesting information to the SmartDashboard.
*/
void Log();
/**
* Use the potentiometer as the PID sensor. This method is automatically
* called by the subsystem.
*/
double ReturnPIDInput();
/**
* Use the motor as the PID output. This method is automatically called by
* the subsystem.
*/
void UsePIDOutput(double d);
};
#endif

View File

@@ -8,7 +8,15 @@
<name>Network Tables</name>
<description>Examples of how to use Network Tables to accomplish a
variety of tasks such as sending and receiving values to both
dashboards and co-processors..</description>
dashboards and co-processors.</description>
</tagDescription>
<tagDescription>
<name>CommandBased Robot</name>
<description>Examples for CommandBased robot programs.</description>
</tagDescription>
<tagDescription>
<name>Simulation</name>
<description>Examples that can be run in simulation.</description>
</tagDescription>
<example>
@@ -43,5 +51,92 @@
<file source="examples/Network Table Counter/Robot.cpp" destination="src/Robot.cpp" />
</files>
</example>
<example>
<name>GearsBot</name>
<description>A fully functional example CommandBased program for
WPIs GearsBot robot. This code can run on your computer if it
supports simulation.</description>
<tags>
<tag>CommandBased Robot</tag>
<tag>Simulation</tag>
</tags>
<packages>
<package>src</package>
<package>src/Commands</package>
<package>src/Subsystems</package>
</packages>
<files>
<file source="examples/GearsBot/src/Commands/Autonomous.cpp"
destination="src/Commands/Autonomous.cpp"></file>
<file source="examples/GearsBot/src/Commands/Autonomous.h"
destination="src/Commands/Autonomous.h"></file>
<file source="examples/GearsBot/src/Commands/CloseClaw.cpp"
destination="src/Commands/CloseClaw.cpp"></file>
<file source="examples/GearsBot/src/Commands/CloseClaw.h"
destination="src/Commands/CloseClaw.h"></file>
<file source="examples/GearsBot/src/Commands/DriveStraight.cpp"
destination="src/Commands/DriveStraight.cpp"></file>
<file source="examples/GearsBot/src/Commands/DriveStraight.h"
destination="src/Commands/DriveStraight.h"></file>
<file source="examples/GearsBot/src/Commands/OpenClaw.cpp"
destination="src/Commands/OpenClaw.cpp"></file>
<file source="examples/GearsBot/src/Commands/OpenClaw.h"
destination="src/Commands/OpenClaw.h"></file>
<file source="examples/GearsBot/src/Commands/Pickup.cpp"
destination="src/Commands/Pickup.cpp"></file>
<file source="examples/GearsBot/src/Commands/Pickup.h"
destination="src/Commands/Pickup.h"></file>
<file source="examples/GearsBot/src/Commands/Place.cpp"
destination="src/Commands/Place.cpp"></file>
<file source="examples/GearsBot/src/Commands/Place.h"
destination="src/Commands/Place.h"></file>
<file source="examples/GearsBot/src/Commands/PrepareToPickup.cpp"
destination="src/Commands/PrepareToPickup.cpp"></file>
<file source="examples/GearsBot/src/Commands/PrepareToPickup.h"
destination="src/Commands/PrepareToPickup.h"></file>
<file source="examples/GearsBot/src/Commands/SetDistanceToBox.cpp"
destination="src/Commands/SetDistanceToBox.cpp"></file>
<file source="examples/GearsBot/src/Commands/SetDistanceToBox.h"
destination="src/Commands/SetDistanceToBox.h"></file>
<file source="examples/GearsBot/src/Commands/SetElevatorSetpoint.cpp"
destination="src/Commands/SetElevatorSetpoint.cpp"></file>
<file source="examples/GearsBot/src/Commands/SetElevatorSetpoint.h"
destination="src/Commands/SetElevatorSetpoint.h"></file>
<file source="examples/GearsBot/src/Commands/SetWristSetpoint.cpp"
destination="src/Commands/SetWristSetpoint.cpp"></file>
<file source="examples/GearsBot/src/Commands/SetWristSetpoint.h"
destination="src/Commands/SetWristSetpoint.h"></file>
<file source="examples/GearsBot/src/Commands/TankDriveWithJoystick.cpp"
destination="src/Commands/TankDriveWithJoystick.cpp"></file>
<file source="examples/GearsBot/src/Commands/TankDriveWithJoystick.h"
destination="src/Commands/TankDriveWithJoystick.h"></file>
<file source="examples/GearsBot/src/OI.cpp"
destination="src/OI.cpp"></file>
<file source="examples/GearsBot/src/OI.h"
destination="src/OI.h"></file>
<file source="examples/GearsBot/src/Robot.cpp"
destination="src/Robot.cpp"></file>
<file source="examples/GearsBot/src/Robot.h"
destination="src/Robot.h"></file>
<file source="examples/GearsBot/src/Subsystems/Claw.cpp"
destination="src/Subsystems/Claw.cpp"></file>
<file source="examples/GearsBot/src/Subsystems/Claw.h"
destination="src/Subsystems/Claw.h"></file>
<file source="examples/GearsBot/src/Subsystems/DriveTrain.cpp"
destination="src/Subsystems/DriveTrain.cpp"></file>
<file source="examples/GearsBot/src/Subsystems/DriveTrain.h"
destination="src/Subsystems/DriveTrain.h"></file>
<file source="examples/GearsBot/src/Subsystems/Elevator.cpp"
destination="src/Subsystems/Elevator.cpp"></file>
<file source="examples/GearsBot/src/Subsystems/Elevator.h"
destination="src/Subsystems/Elevator.h"></file>
<file source="examples/GearsBot/src/Subsystems/Wrist.cpp"
destination="src/Subsystems/Wrist.cpp"></file>
<file source="examples/GearsBot/src/Subsystems/Wrist.h"
destination="src/Subsystems/Wrist.h"></file>
</files>
</example>
</examples>