mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
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:
committed by
thomasclark
parent
d5a509c7e7
commit
cb56c9a144
@@ -180,6 +180,41 @@
|
||||
mode="debug">
|
||||
</description>
|
||||
</shortcut>
|
||||
<shortcut
|
||||
class="edu.wpi.first.wpilib.plugins.cpp.launching.SimulateLaunchShortcut"
|
||||
description="Test the WPILib project using the Gazebo simulator."
|
||||
icon="resources/icons/wpi.ico"
|
||||
id="edu.wpi.first.wpilib.plugins.cpp.launching.simulate"
|
||||
label="WPILib Simulate"
|
||||
modes="run,debug">
|
||||
<contextualLaunch>
|
||||
<enablement>
|
||||
<with
|
||||
variable="selection">
|
||||
<iterate>
|
||||
<and>
|
||||
<test
|
||||
value="edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature"
|
||||
property="org.eclipse.core.resources.projectNature">
|
||||
</test>
|
||||
<test
|
||||
value="org.eclipse.cdt.core.cnature"
|
||||
property="org.eclipse.core.resources.projectNature">
|
||||
</test>
|
||||
</and>
|
||||
</iterate>
|
||||
</with>
|
||||
</enablement>
|
||||
</contextualLaunch>
|
||||
<description
|
||||
description="Test the WPILib project using the Gazebo simulator."
|
||||
mode="run">
|
||||
</description>
|
||||
<description
|
||||
description="Debug the WPILib project using the Gazebo simulator."
|
||||
mode="debug">
|
||||
</description>
|
||||
</shortcut>
|
||||
</extension>
|
||||
<extension
|
||||
point="org.eclipse.ui.startup">
|
||||
|
||||
@@ -63,9 +63,16 @@
|
||||
<groupId>edu.wpi.first.wpilib.cmake</groupId>
|
||||
<artifactId>cpp-root</artifactId>
|
||||
<version>1.0.0</version>
|
||||
<type>zip</type>
|
||||
<type>zip</type>
|
||||
<destFileName>cpp-root.jar</destFileName>
|
||||
</artifactItem>
|
||||
<artifactItem>
|
||||
<groupId>edu.wpi.first.wpilibc.simulation</groupId>
|
||||
<artifactId>WPILibCSim</artifactId>
|
||||
<version>0.1.0</version>
|
||||
<type>zip</type>
|
||||
<destFileName>sim-include.zip</destFileName>
|
||||
</artifactItem>
|
||||
</artifactItems>
|
||||
<outputDirectory>${project.build.directory}</outputDirectory>
|
||||
<overWriteReleases>false</overWriteReleases>
|
||||
@@ -73,6 +80,38 @@
|
||||
<prependGroupId>true</prependGroupId>
|
||||
</configuration>
|
||||
</execution>
|
||||
|
||||
<!-- Simulation -->
|
||||
<execution>
|
||||
<id>fetch-sim-jar-zip-dependencies</id>
|
||||
<phase>compile</phase>
|
||||
<goals>
|
||||
<goal>copy</goal>
|
||||
</goals>
|
||||
<configuration>
|
||||
<outputDirectory>${cpp-zip}/sim/lib</outputDirectory>
|
||||
<overWriteReleases>false</overWriteReleases>
|
||||
<overWriteSnapshots>true</overWriteSnapshots>
|
||||
|
||||
<artifactItems>
|
||||
<artifactItem>
|
||||
<groupId>net.java.jinput</groupId>
|
||||
<artifactId>jinput-platform</artifactId>
|
||||
<version>2.0.5</version>
|
||||
<classifier>natives-linux</classifier>
|
||||
<type>jar</type>
|
||||
</artifactItem>
|
||||
|
||||
<artifactItem>
|
||||
<groupId>edu.wpi.first.wpilibj.simulation</groupId>
|
||||
<artifactId>SimDS</artifactId>
|
||||
<version>0.1.0-SNAPSHOT</version>
|
||||
<destFileName>SimDS.jar</destFileName>
|
||||
<outputDirectory>${cpp-zip}/sim/tools</outputDirectory>
|
||||
</artifactItem>
|
||||
</artifactItems>
|
||||
</configuration>
|
||||
</execution>
|
||||
</executions>
|
||||
</plugin>
|
||||
<plugin>
|
||||
@@ -80,6 +119,7 @@
|
||||
<artifactId>maven-antrun-plugin</artifactId>
|
||||
<version>1.7</version>
|
||||
<executions>
|
||||
|
||||
<!-- Set time stamp and version properties. -->
|
||||
<execution>
|
||||
<id>set-version-info</id>
|
||||
@@ -100,6 +140,7 @@
|
||||
<exportAntProperties>true</exportAntProperties>
|
||||
</configuration>
|
||||
</execution>
|
||||
|
||||
<!-- Unzip the include files for cpp.zip. -->
|
||||
<execution>
|
||||
<id>unzip-cpp-includes</id>
|
||||
@@ -112,11 +153,29 @@
|
||||
<unzip dest="${cpp-zip}">
|
||||
<fileset dir="${project.build.directory}">
|
||||
<include name="cpp-root.jar"/>
|
||||
<include name="sim-include.zip"/>
|
||||
</fileset>
|
||||
</unzip>
|
||||
</target>
|
||||
</configuration>
|
||||
</execution>
|
||||
|
||||
<!-- Unzip jinput *.so's -->
|
||||
<execution>
|
||||
<id>unzip-jinput-libs</id>
|
||||
<phase>compile</phase>
|
||||
<goals>
|
||||
<goal>run</goal>
|
||||
</goals>
|
||||
<configuration>
|
||||
<target>
|
||||
<unzip src="${cpp-zip}/sim/lib/jinput-platform-2.0.5-natives-linux.jar"
|
||||
dest="${cpp-zip}/sim/lib"
|
||||
overwrite="true" />
|
||||
</target>
|
||||
</configuration>
|
||||
</execution>
|
||||
|
||||
<!-- Generate zip file to unzip for the user. -->
|
||||
<execution>
|
||||
<id>generate-cpp-zip</id>
|
||||
@@ -141,5 +200,11 @@
|
||||
<version>1.0.0</version>
|
||||
<type>zip</type>
|
||||
</dependency>
|
||||
<dependency>
|
||||
<groupId>edu.wpi.first.wpilibc.simulation</groupId>
|
||||
<artifactId>WPILibCSim</artifactId>
|
||||
<version>0.1.0</version>
|
||||
<type>zip</type>
|
||||
</dependency>
|
||||
</dependencies>
|
||||
</project>
|
||||
|
||||
@@ -128,6 +128,76 @@
|
||||
</storageModule>
|
||||
<storageModule moduleId="org.eclipse.cdt.core.externalSettings"/>
|
||||
</cconfiguration>
|
||||
<cconfiguration id="cdt.managedbuild.config.gnu.cross.exe.debug.418253318.2017904325">
|
||||
<storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="cdt.managedbuild.config.gnu.cross.exe.debug.418253318.2017904325" moduleId="org.eclipse.cdt.core.settings" name="Simulate">
|
||||
<externalSettings/>
|
||||
<extensions>
|
||||
<extension id="org.eclipse.cdt.core.GCCErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||
<extension id="org.eclipse.cdt.core.GASErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||
<extension id="org.eclipse.cdt.core.GLDErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||
<extension id="org.eclipse.cdt.core.GmakeErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||
<extension id="org.eclipse.cdt.core.CWDLocator" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||
<extension id="org.eclipse.cdt.core.ELF" point="org.eclipse.cdt.core.BinaryParser"/>
|
||||
</extensions>
|
||||
</storageModule>
|
||||
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
|
||||
<configuration artifactName="FRCUserProgram" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.debug,org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe" cleanCommand="rm -rf" description="" errorParsers="org.eclipse.cdt.core.GCCErrorParser;org.eclipse.cdt.core.GASErrorParser;org.eclipse.cdt.core.GLDErrorParser;org.eclipse.cdt.core.CWDLocator;org.eclipse.cdt.core.GmakeErrorParser" id="cdt.managedbuild.config.gnu.cross.exe.debug.418253318.2017904325" name="Simulate" parent="cdt.managedbuild.config.gnu.cross.exe.debug" postannouncebuildStep="" postbuildStep="" preannouncebuildStep="" prebuildStep="">
|
||||
<folderInfo id="cdt.managedbuild.config.gnu.cross.exe.debug.418253318.2017904325." name="/" resourcePath="">
|
||||
<toolChain errorParsers="" id="cdt.managedbuild.toolchain.gnu.base.1184188597" name="Linux GCC" superClass="cdt.managedbuild.toolchain.gnu.base">
|
||||
<targetPlatform archList="all" binaryParser="org.eclipse.cdt.core.ELF" id="cdt.managedbuild.target.gnu.platform.base.1621111203" name="Debug Platform" osList="linux,hpux,aix,qnx" superClass="cdt.managedbuild.target.gnu.platform.base"/>
|
||||
<builder buildPath="${workspace_loc:/${ProjName}}/Simulate" errorParsers="org.eclipse.cdt.core.GmakeErrorParser;org.eclipse.cdt.core.CWDLocator" id="cdt.managedbuild.target.gnu.builder.base.840272037" keepEnvironmentInBuildfile="false" name="Gnu Make Builder" superClass="cdt.managedbuild.target.gnu.builder.base"/>
|
||||
<tool id="cdt.managedbuild.tool.gnu.archiver.base.158466008" name="GCC Archiver" superClass="cdt.managedbuild.tool.gnu.archiver.base"/>
|
||||
<tool command="g++" commandLinePattern="${COMMAND} ${FLAGS} ${OUTPUT_FLAG} ${OUTPUT_PREFIX}${OUTPUT} ${INPUTS}" errorParsers="org.eclipse.cdt.core.GCCErrorParser" id="cdt.managedbuild.tool.gnu.cpp.compiler.base.2105416021" name="GCC C++ Compiler" superClass="cdt.managedbuild.tool.gnu.cpp.compiler.base">
|
||||
<option id="gnu.cpp.compiler.option.include.paths.1645322059" name="Include paths (-I)" superClass="gnu.cpp.compiler.option.include.paths" valueType="includePath">
|
||||
<listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}}/src""/>
|
||||
<listOptionValue builtIn="false" value="$cpp-location/sim/include"/>
|
||||
<listOptionValue builtIn="false" value="/usr/include"/>
|
||||
<listOptionValue builtIn="false" value="/usr/include/gazebo-2.2"/>
|
||||
<listOptionValue builtIn="false" value="/usr/include/sdformat-1.4"/>
|
||||
</option>
|
||||
<option id="gnu.cpp.compiler.option.optimization.level.1648211502" name="Optimization Level" superClass="gnu.cpp.compiler.option.optimization.level" value="gnu.cpp.compiler.optimization.level.none" valueType="enumerated"/>
|
||||
<option id="gnu.cpp.compiler.option.debugging.level.937474733" name="Debug Level" superClass="gnu.cpp.compiler.option.debugging.level" value="gnu.cpp.compiler.debugging.level.max" valueType="enumerated"/>
|
||||
<inputType id="cdt.managedbuild.tool.gnu.cpp.compiler.input.1758810658" superClass="cdt.managedbuild.tool.gnu.cpp.compiler.input"/>
|
||||
</tool>
|
||||
<tool command="gcc" commandLinePattern="${COMMAND} ${FLAGS} ${OUTPUT_FLAG} ${OUTPUT_PREFIX}${OUTPUT} ${INPUTS}" errorParsers="org.eclipse.cdt.core.GCCErrorParser" id="cdt.managedbuild.tool.gnu.c.compiler.base.2039239712" name="GCC C Compiler" superClass="cdt.managedbuild.tool.gnu.c.compiler.base">
|
||||
<option defaultValue="gnu.c.optimization.level.none" id="gnu.c.compiler.option.optimization.level.2100353684" name="Optimization Level" superClass="gnu.c.compiler.option.optimization.level" valueType="enumerated"/>
|
||||
<option id="gnu.c.compiler.option.debugging.level.1900634657" name="Debug Level" superClass="gnu.c.compiler.option.debugging.level" value="gnu.c.debugging.level.max" valueType="enumerated"/>
|
||||
<inputType id="cdt.managedbuild.tool.gnu.c.compiler.input.1197133064" superClass="cdt.managedbuild.tool.gnu.c.compiler.input"/>
|
||||
</tool>
|
||||
<tool id="cdt.managedbuild.tool.gnu.c.linker.base.66697269" name="GCC C Linker" superClass="cdt.managedbuild.tool.gnu.c.linker.base"/>
|
||||
<tool command="g++" commandLinePattern="${COMMAND} ${FLAGS} ${OUTPUT_FLAG} ${OUTPUT_PREFIX}${OUTPUT} ${INPUTS}" errorParsers="org.eclipse.cdt.core.GLDErrorParser" id="cdt.managedbuild.tool.gnu.cpp.linker.base.2094820582" name="GCC C++ Linker" superClass="cdt.managedbuild.tool.gnu.cpp.linker.base">
|
||||
<option id="gnu.cpp.link.option.libs.1563598353" name="Libraries (-l)" superClass="gnu.cpp.link.option.libs" valueType="libs">
|
||||
<listOptionValue builtIn="false" value="WPILibSim"/>
|
||||
<listOptionValue builtIn="false" value="gazebo"/>
|
||||
<listOptionValue builtIn="false" value="gazebo_transport"/>
|
||||
<listOptionValue builtIn="false" value="gazebo_msgs"/>
|
||||
<listOptionValue builtIn="false" value="gazebo_common"/>
|
||||
<listOptionValue builtIn="false" value="protobuf"/>
|
||||
<listOptionValue builtIn="false" value="boost_system"/>
|
||||
<listOptionValue builtIn="false" value="dl"/>
|
||||
<listOptionValue builtIn="false" value="pthread"/>
|
||||
</option>
|
||||
<option id="gnu.cpp.link.option.paths.1677933356" name="Library search path (-L)" superClass="gnu.cpp.link.option.paths" valueType="libPaths">
|
||||
<listOptionValue builtIn="false" value="/usr/lib/x86_64-linux-gnu"/>
|
||||
<listOptionValue builtIn="false" value="/usr/lib/x86_64-linux-gnu/gazebo-2.2/plugins"/>
|
||||
</option>
|
||||
<inputType id="cdt.managedbuild.tool.gnu.cpp.linker.input.152327207" superClass="cdt.managedbuild.tool.gnu.cpp.linker.input">
|
||||
<additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/>
|
||||
<additionalInput kind="additionalinput" paths="$(LIBS)"/>
|
||||
</inputType>
|
||||
</tool>
|
||||
<tool command="as" commandLinePattern="${COMMAND} ${FLAGS} ${OUTPUT_FLAG} ${OUTPUT_PREFIX}${OUTPUT} ${INPUTS}" errorParsers="org.eclipse.cdt.core.GASErrorParser" id="cdt.managedbuild.tool.gnu.assembler.base.2105089872" name="GCC Assembler" superClass="cdt.managedbuild.tool.gnu.assembler.base">
|
||||
<inputType id="cdt.managedbuild.tool.gnu.assembler.input.254601899" superClass="cdt.managedbuild.tool.gnu.assembler.input"/>
|
||||
</tool>
|
||||
</toolChain>
|
||||
</folderInfo>
|
||||
<sourceEntries>
|
||||
<entry flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name="src"/>
|
||||
</sourceEntries>
|
||||
</configuration>
|
||||
</storageModule>
|
||||
<storageModule moduleId="org.eclipse.cdt.core.externalSettings"/>
|
||||
</cconfiguration>
|
||||
</storageModule>
|
||||
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
|
||||
<project id="$project.cdt.managedbuild.target.gnu.cross.exe.548740421" name="Executable" projectType="cdt.managedbuild.target.gnu.cross.exe"/>
|
||||
@@ -195,5 +265,8 @@
|
||||
<configuration configurationName="Debug">
|
||||
<resource resourceType="PROJECT" workspacePath="/$project"/>
|
||||
</configuration>
|
||||
<configuration configurationName="Simulate">
|
||||
<resource resourceType="PROJECT" workspacePath="/$project"/>
|
||||
</configuration>
|
||||
</storageModule>
|
||||
</cproject>
|
||||
|
||||
@@ -18,4 +18,11 @@ classloadertask.jar=${wpilib.ant.dir}/ant-classloadertask.jar
|
||||
out=FRCUserProgram
|
||||
src.dir=src
|
||||
build.dir=build
|
||||
out.exe=Debug/${out}
|
||||
out.exe=Debug/${out}
|
||||
|
||||
# Simulation
|
||||
simulation.world.file=$world
|
||||
sim.exe=Simulate/${out}
|
||||
wpilib.sim=${wpilib}/sim
|
||||
sim.tools=${wpilib.sim}/tools
|
||||
sim.lib=${wpilib.sim}/lib
|
||||
@@ -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());
|
||||
}
|
||||
@@ -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
|
||||
@@ -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();
|
||||
}
|
||||
@@ -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
|
||||
@@ -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);
|
||||
}
|
||||
@@ -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
|
||||
@@ -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();
|
||||
}
|
||||
@@ -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
|
||||
@@ -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));
|
||||
}
|
||||
@@ -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
|
||||
@@ -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());
|
||||
}
|
||||
@@ -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
|
||||
@@ -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));
|
||||
}
|
||||
@@ -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
|
||||
@@ -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);
|
||||
}
|
||||
@@ -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
|
||||
@@ -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() {}
|
||||
@@ -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
|
||||
@@ -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() {}
|
||||
@@ -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
|
||||
@@ -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();
|
||||
}
|
||||
@@ -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
|
||||
@@ -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;
|
||||
}
|
||||
@@ -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_ */
|
||||
@@ -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);
|
||||
@@ -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_ */
|
||||
@@ -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();
|
||||
}
|
||||
|
||||
@@ -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
|
||||
@@ -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();
|
||||
}
|
||||
@@ -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
|
||||
@@ -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);
|
||||
}
|
||||
@@ -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
|
||||
@@ -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);
|
||||
}
|
||||
@@ -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
|
||||
@@ -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>
|
||||
|
||||
@@ -0,0 +1,137 @@
|
||||
package edu.wpi.first.wpilib.plugins.cpp.launching;
|
||||
|
||||
import java.io.File;
|
||||
import java.lang.reflect.Method;
|
||||
import java.util.Vector;
|
||||
|
||||
import org.eclipse.core.internal.resources.Resource;
|
||||
import org.eclipse.core.resources.IFile;
|
||||
import org.eclipse.core.resources.IProject;
|
||||
import org.eclipse.debug.core.ILaunch;
|
||||
import org.eclipse.debug.core.ILaunchManager;
|
||||
import org.eclipse.debug.ui.IDebugUIConstants;
|
||||
import org.eclipse.debug.ui.ILaunchShortcut;
|
||||
import org.eclipse.jface.viewers.ISelection;
|
||||
import org.eclipse.jface.viewers.StructuredSelection;
|
||||
import org.eclipse.ui.IEditorPart;
|
||||
import org.eclipse.ui.IFileEditorInput;
|
||||
import org.eclipse.ui.PlatformUI;
|
||||
|
||||
import edu.wpi.first.wpilib.plugins.core.launching.AntLauncher;
|
||||
|
||||
/**
|
||||
* Launch shortcut base functionality, common for deploying to the robot.
|
||||
* Retrieves the project the operation is being called on, and runs the correct
|
||||
* ant targets based on polymorphically determined data values
|
||||
*
|
||||
* @author Ryan O'Meara
|
||||
* @author Alex Henning
|
||||
*/
|
||||
@SuppressWarnings("restriction")
|
||||
public class SimulateLaunchShortcut implements ILaunchShortcut {
|
||||
//Class constants - used to delineate types for launch shortcuts
|
||||
public static final String DEPLOY_TYPE = "edu.wpi.first.wpilib.plugins.core.deploy";
|
||||
private static final String ANT_SERVER_THREAD_NAME = "Ant Build Server Connection";
|
||||
|
||||
private static ILaunch lastDeploy = null;
|
||||
|
||||
/**
|
||||
* Returns the launch type of the shortcut that was used, one of the constants
|
||||
* defined in BaseLaunchShortcut
|
||||
* @return Launch shortcut type
|
||||
*/
|
||||
public String getLaunchType() {return DEPLOY_TYPE;}
|
||||
|
||||
@Override
|
||||
public void launch(ISelection selection, String mode) {
|
||||
//Extract resource from selection
|
||||
StructuredSelection sel = (StructuredSelection)selection;
|
||||
IProject activeProject = null;
|
||||
if (sel.getFirstElement() instanceof IProject) {
|
||||
activeProject = (IProject) sel.getFirstElement();
|
||||
} else {
|
||||
return;
|
||||
}
|
||||
|
||||
//Run config using project found in extracted resource, with indicated mode
|
||||
runConfig(activeProject, mode);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void launch(IEditorPart editor, String mode) {
|
||||
//Extract resource from editor
|
||||
if(editor != null){
|
||||
IFileEditorInput input = (IFileEditorInput)editor.getEditorInput();
|
||||
IFile file = input.getFile();
|
||||
IProject activeProject = file.getProject();
|
||||
|
||||
//If editor existed, run config using extracted resource in indicated mode
|
||||
runConfig(activeProject, mode);
|
||||
}else{
|
||||
System.err.println("editor was null");
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* Runs the ant script using the correct target for the indicated mode (deploy to cRIO or just compile)
|
||||
* @param activeProj The project that the script will be run on/from
|
||||
* @param mode The mode it will be run in (ILaunchManager.RUN_MODE or ILaunchManager.DEBUG_MODE)
|
||||
*/
|
||||
public void runConfig(IProject activeProj, String mode){
|
||||
String targets = "simulate";
|
||||
|
||||
if(mode.equals(ILaunchManager.RUN_MODE)){
|
||||
if(getLaunchType().equals(DEPLOY_TYPE)){
|
||||
targets = "simulate";
|
||||
}
|
||||
} else if ((mode.equals(ILaunchManager.DEBUG_MODE))&&(getLaunchType().equals(DEPLOY_TYPE))) {
|
||||
targets = "debug-simulate";
|
||||
try{
|
||||
PlatformUI.getWorkbench().showPerspective(IDebugUIConstants.ID_DEBUG_PERSPECTIVE,
|
||||
PlatformUI.getWorkbench().getActiveWorkbenchWindow());
|
||||
|
||||
}catch(Exception e){}
|
||||
}
|
||||
|
||||
if((lastDeploy != null)&&(!lastDeploy.isTerminated())){
|
||||
System.out.println("Last deploy running");
|
||||
//Find the server connection thread and kill it
|
||||
Vector<ThreadGroup> threadGroups = new Vector<ThreadGroup>();
|
||||
ThreadGroup root = Thread.currentThread().getThreadGroup().getParent();
|
||||
while (root.getParent() != null) {root = root.getParent();}
|
||||
threadGroups.add(root);
|
||||
ThreadGroup threadGroup = threadGroups.remove(0);
|
||||
int numThreads = threadGroup.activeCount();
|
||||
Thread[] threads = new Thread[numThreads*100];
|
||||
numThreads = threadGroup.enumerate(threads, true);
|
||||
|
||||
for(Thread current: threads){
|
||||
if(current != null){
|
||||
if(current.getName().equals(ANT_SERVER_THREAD_NAME)){
|
||||
try{
|
||||
//Manually end thread and then try terminating launch
|
||||
Method stopMethod = current.getClass().getMethod("stop");
|
||||
stopMethod.invoke(current);
|
||||
lastDeploy.terminate();
|
||||
break;
|
||||
}catch(Exception e){e.printStackTrace();}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
System.out.println("Waiting");
|
||||
try{wait(1000);}catch(Exception e){}
|
||||
|
||||
}
|
||||
|
||||
System.out.println("Running ant file: " + activeProj.getLocation().toOSString() + File.separator + "build.xml");
|
||||
System.out.println("Targets: " + targets + ", Mode: " + mode);
|
||||
lastDeploy = AntLauncher.runAntFile(new File (activeProj.getLocation().toOSString() + File.separator + "build.xml"), targets, null, mode);
|
||||
|
||||
try {
|
||||
activeProj.refreshLocal(Resource.DEPTH_INFINITE, null);
|
||||
} catch (Exception e) {}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -34,7 +34,7 @@ public class ExampleCPPWizard extends ExampleWizard {
|
||||
WPILibCore.getDefault().saveGlobalProperties(props);
|
||||
|
||||
final String projectName = detailsPage.getProjectName();
|
||||
ProjectCreationUtils.createProject(new WPIRobotCPPProjectCreator(projectName, ex));
|
||||
ProjectCreationUtils.createProject(new WPIRobotCPPProjectCreator(projectName, ex, detailsPage.getWorld()));
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -72,11 +72,12 @@ public class NewCPPWizard extends Wizard implements INewWizard {
|
||||
final String projectName = page.getProjectName();
|
||||
final String teamNumber = TeamNumberPage.getTeamNumberFromPage(teamNumberPage);
|
||||
final ProjectType projectType = page.getProjectType();
|
||||
final String worldName = page.getWorld();
|
||||
System.out.println("Project: "+projectName+" Project Type: "+projectType);
|
||||
IRunnableWithProgress op = new IRunnableWithProgress() {
|
||||
public void run(IProgressMonitor monitor) throws InvocationTargetException {
|
||||
try {
|
||||
doFinish(projectName, teamNumber, projectType, monitor);
|
||||
doFinish(projectName, teamNumber, projectType, worldName, monitor);
|
||||
} catch (CoreException e) {
|
||||
throw new InvocationTargetException(e);
|
||||
} finally {
|
||||
@@ -102,11 +103,11 @@ public class NewCPPWizard extends Wizard implements INewWizard {
|
||||
* the editor on the newly created file.
|
||||
*/
|
||||
|
||||
private void doFinish(String projectName, String teamNumber, ProjectType projectType, IProgressMonitor monitor) throws CoreException {
|
||||
private void doFinish(String projectName, String teamNumber, ProjectType projectType, String worldName, IProgressMonitor monitor) throws CoreException {
|
||||
Properties props = WPILibCore.getDefault().getProjectProperties(null);
|
||||
props.setProperty("team-number", teamNumber);
|
||||
WPILibCore.getDefault().saveGlobalProperties(props);
|
||||
ProjectCreationUtils.createProject(new WPIRobotCPPProjectCreator(projectName, projectType));
|
||||
ProjectCreationUtils.createProject(new WPIRobotCPPProjectCreator(projectName, projectType, worldName));
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -22,10 +22,12 @@ import edu.wpi.first.wpilib.plugins.cpp.WPILibCPPPlugin;
|
||||
public class WPIRobotCPPProjectCreator implements IProjectCreator {
|
||||
String projectName;
|
||||
ProjectType projectType;
|
||||
private String worldName;
|
||||
|
||||
public WPIRobotCPPProjectCreator(String projectName, ProjectType projectType) {
|
||||
public WPIRobotCPPProjectCreator(String projectName, ProjectType projectType, String worldName) {
|
||||
this.projectName = projectName;
|
||||
this.projectType = projectType;
|
||||
this.worldName = worldName;
|
||||
}
|
||||
|
||||
@Override
|
||||
@@ -44,6 +46,7 @@ public class WPIRobotCPPProjectCreator implements IProjectCreator {
|
||||
vals.put("$project", projectName);
|
||||
vals.put("$toolchain", WPILibCPPPlugin.getDefault().getToolchain());
|
||||
vals.put("$cpp-location", WPILibCPPPlugin.getDefault().getCPPDir());
|
||||
vals.put("$world", worldName);
|
||||
return vals;
|
||||
}
|
||||
|
||||
|
||||
@@ -147,4 +147,28 @@ ${md5.hal} usr/local/frc/lib/libHALAthena.so</echo>
|
||||
trust="true"
|
||||
command="chmod a+x debug*program; ${deploy.debug.command}"/>
|
||||
</target>
|
||||
|
||||
<!-- Simulation support -->
|
||||
<target name="simulate">
|
||||
<parallel>
|
||||
<sequential>
|
||||
<echo>[simulate] Running Gazebo.</echo>
|
||||
<exec executable="frcsim">
|
||||
<arg value="${simulation.world.file}"/>
|
||||
</exec>
|
||||
</sequential>
|
||||
<sequential>
|
||||
<sleep seconds="5"/>
|
||||
<echo>[simulate] Running DriverStation.</echo>
|
||||
<java jar="${sim.tools}/SimDS.jar" fork="true">
|
||||
<jvmarg value="-Djava.library.path=${sim.lib}" />
|
||||
</java>
|
||||
</sequential>
|
||||
<sequential>
|
||||
<sleep seconds="5"/>
|
||||
<echo>[simulate] Running Code.</echo>
|
||||
<exec executable="${sim.exe}"></exec>
|
||||
</sequential>
|
||||
</parallel>
|
||||
</target>
|
||||
</project>
|
||||
|
||||
Reference in New Issue
Block a user