From 7ba84ea54dee3e3a6abb246fc964f6543b679a87 Mon Sep 17 00:00:00 2001 From: cbennet <42650450+cbennet@users.noreply.github.com> Date: Sun, 18 Oct 2020 16:40:17 -0400 Subject: [PATCH] New command framework for C++ (#248) Update to export New Command Framework. Fixes #191 Use uniform initialization in header. Fixes #80 Co-authored-by: Joe --- .../robotbuilder/actions/ExporterAction.java | 4 +- .../export/cpp/Command-constructor-header.h | 6 +- .../cpp/Command-constructor-variables.h | 13 + .../export/cpp/Command-constructor.cpp | 32 +-- .../resources/export/cpp/Command-disabled.cpp | 6 + .../resources/export/cpp/Command-requires.cpp | 4 - src/main/resources/export/cpp/Command.cpp | 14 +- src/main/resources/export/cpp/Command.h | 23 +- .../cpp/CommandBasedRobot-autonomous.cpp | 8 +- .../cpp/CommandBasedRobot-declarations.cpp | 2 +- .../export/cpp/CommandBasedRobot-includes.h | 4 +- .../cpp/CommandBasedRobot-initialization.cpp | 3 +- .../export/cpp/CommandBasedRobot.cpp | 98 ++++---- .../resources/export/cpp/CommandBasedRobot.h | 43 ++-- .../export/cpp/CommandGroup-constructor.cpp | 13 - .../export/cpp/CommandGroup-declarations.cpp | 5 - .../resources/export/cpp/CommandGroup.cpp | 34 --- src/main/resources/export/cpp/CommandGroup.h | 23 -- .../cpp/ConditionalCommand-constructor.cpp | 5 +- .../export/cpp/ConditionalCommand-includes.h | 4 +- .../export/cpp/ConditionalCommand.cpp | 6 +- .../export/cpp/ExportDescription.yaml | 233 ++++++++++-------- .../export/cpp/InstantCommand-constructor.cpp | 17 +- .../resources/export/cpp/InstantCommand.cpp | 4 +- .../resources/export/cpp/InstantCommand.h | 11 +- .../resources/export/cpp/OI-constructors.cpp | 25 -- .../resources/export/cpp/OI-declarations.h | 7 - src/main/resources/export/cpp/OI-includes.h | 2 - src/main/resources/export/cpp/OI-prototypes.h | 8 - src/main/resources/export/cpp/OI.cpp | 18 -- src/main/resources/export/cpp/OI.h | 20 -- .../export/cpp/PIDCommand-constructor.cpp | 44 +++- .../export/cpp/PIDCommand-includes.h | 4 + .../export/cpp/PIDCommand-output.cpp | 2 +- .../resources/export/cpp/PIDCommand-pid.cpp | 8 +- .../export/cpp/PIDCommand-source.cpp | 2 +- src/main/resources/export/cpp/PIDCommand.cpp | 15 +- src/main/resources/export/cpp/PIDCommand.h | 26 +- .../export/cpp/PIDSubsystem-output.cpp | 2 +- .../resources/export/cpp/PIDSubsystem-pid.cpp | 12 +- .../export/cpp/PIDSubsystem-source.cpp | 2 +- .../resources/export/cpp/PIDSubsystem.cpp | 7 +- src/main/resources/export/cpp/PIDSubsystem.h | 22 +- .../cpp/RobotContainer-constructors.cpp | 40 +++ .../export/cpp/RobotContainer-declarations.h | 18 ++ ...tions.cpp => RobotContainer-functions.cpp} | 0 .../export/cpp/RobotContainer-includes.h | 13 + .../export/cpp/RobotContainer-prototypes.h | 8 + ...botContainer-subsystem-default_command.cpp | 12 + .../resources/export/cpp/RobotContainer.cpp | 44 ++++ .../resources/export/cpp/RobotContainer.h | 29 +++ .../export/cpp/SequentialCommandGroup.cpp | 16 ++ .../export/cpp/SequentialCommandGroup.h | 32 +++ .../cpp/SetpointCommand-constructor-header.h | 4 +- .../cpp/SetpointCommand-constructor.cpp | 6 +- .../export/cpp/SetpointCommand-includes.h | 4 + .../export/cpp/SetpointCommand-initialize.cpp | 4 +- .../export/cpp/SetpointCommand-isFinished.cpp | 2 +- .../resources/export/cpp/SetpointCommand.cpp | 6 +- .../resources/export/cpp/SetpointCommand.h | 19 +- .../export/cpp/Subsystem-constants.cpp | 5 - .../export/cpp/Subsystem-constants.h | 2 +- .../export/cpp/Subsystem-declarations.cpp | 2 - .../export/cpp/Subsystem-declarations.h | 2 +- .../export/cpp/Subsystem-default_command.cpp | 9 - .../export/cpp/Subsystem-includes.cpp | 6 +- .../resources/export/cpp/Subsystem-includes.h | 1 + .../export/cpp/Subsystem-pidgetters.cpp | 8 +- .../export/cpp/Subsystem-pidgetters.h | 4 +- src/main/resources/export/cpp/Subsystem.cpp | 17 +- src/main/resources/export/cpp/Subsystem.h | 20 +- .../export/cpp/TimedCommand-constructor.cpp | 15 +- .../resources/export/cpp/TimedCommand.cpp | 4 +- src/main/resources/export/cpp/TimedCommand.h | 8 +- .../resources/export/cpp/command-includes.h | 7 + src/main/resources/export/cpp/files.yaml | 94 ++++--- src/main/resources/export/cpp/macros.vm | 56 +++-- src/test/java/robotbuilder/TestUtils.java | 1 - 78 files changed, 732 insertions(+), 627 deletions(-) create mode 100644 src/main/resources/export/cpp/Command-disabled.cpp delete mode 100644 src/main/resources/export/cpp/Command-requires.cpp delete mode 100644 src/main/resources/export/cpp/CommandGroup-constructor.cpp delete mode 100644 src/main/resources/export/cpp/CommandGroup-declarations.cpp delete mode 100644 src/main/resources/export/cpp/CommandGroup.cpp delete mode 100644 src/main/resources/export/cpp/CommandGroup.h delete mode 100644 src/main/resources/export/cpp/OI-constructors.cpp delete mode 100644 src/main/resources/export/cpp/OI-declarations.h delete mode 100644 src/main/resources/export/cpp/OI-includes.h delete mode 100644 src/main/resources/export/cpp/OI-prototypes.h delete mode 100644 src/main/resources/export/cpp/OI.cpp delete mode 100644 src/main/resources/export/cpp/OI.h create mode 100644 src/main/resources/export/cpp/PIDCommand-includes.h create mode 100644 src/main/resources/export/cpp/RobotContainer-constructors.cpp create mode 100644 src/main/resources/export/cpp/RobotContainer-declarations.h rename src/main/resources/export/cpp/{OI-functions.cpp => RobotContainer-functions.cpp} (100%) create mode 100644 src/main/resources/export/cpp/RobotContainer-includes.h create mode 100644 src/main/resources/export/cpp/RobotContainer-prototypes.h create mode 100644 src/main/resources/export/cpp/RobotContainer-subsystem-default_command.cpp create mode 100644 src/main/resources/export/cpp/RobotContainer.cpp create mode 100644 src/main/resources/export/cpp/RobotContainer.h create mode 100644 src/main/resources/export/cpp/SequentialCommandGroup.cpp create mode 100644 src/main/resources/export/cpp/SequentialCommandGroup.h create mode 100644 src/main/resources/export/cpp/SetpointCommand-includes.h delete mode 100644 src/main/resources/export/cpp/Subsystem-constants.cpp delete mode 100644 src/main/resources/export/cpp/Subsystem-default_command.cpp create mode 100644 src/main/resources/export/cpp/command-includes.h diff --git a/src/main/java/robotbuilder/actions/ExporterAction.java b/src/main/java/robotbuilder/actions/ExporterAction.java index e1d3c5d6..6d0131ea 100644 --- a/src/main/java/robotbuilder/actions/ExporterAction.java +++ b/src/main/java/robotbuilder/actions/ExporterAction.java @@ -33,13 +33,13 @@ public ExporterAction(String description) { @Override public void actionPerformed(ActionEvent ae) { boolean newProject = false; - MainFrame.getInstance().setCursor(Cursor.WAIT_CURSOR); + MainFrame.getInstance().setCursor(new Cursor(Cursor.WAIT_CURSOR)); try { newProject = exporter.export(MainFrame.getInstance().getCurrentRobotTree()); } catch (IOException ex) { Logger.getLogger(ExporterAction.class.getName()).log(Level.SEVERE, null, ex); } - MainFrame.getInstance().setCursor(Cursor.DEFAULT_CURSOR); + MainFrame.getInstance().setCursor(new Cursor(Cursor.DEFAULT_CURSOR)); if (newProject) JOptionPane.showMessageDialog(MainFrame.getInstance(), "Project successfully exported for the first time. Open project directory in" diff --git a/src/main/resources/export/cpp/Command-constructor-header.h b/src/main/resources/export/cpp/Command-constructor-header.h index d65bc5ac..9a8de4b5 100644 --- a/src/main/resources/export/cpp/Command-constructor-header.h +++ b/src/main/resources/export/cpp/Command-constructor-header.h @@ -3,7 +3,9 @@ #set($len = $params.size() - 2) #set($last = $len + 1) #if( $params.size() > 0 ) - #class($command.name)(#if( $len >= 0 )#foreach($i in [0..$len])#param_declaration_cpp($params.get($i)), #end#end#param_declaration_cpp($params.get($last))); + explicit #class($command.name)(#if( $len >= 0 )#foreach($i in [0..$len])#param_declaration_cpp($params.get($i)), #end#end#param_declaration_cpp($params.get($last))#if (${command.getProperty("Requires").getValue()} != "None"), #class(${command.getProperty("Requires").getValue()})* #variable(${command.getProperty("Requires").getValue().toLowerCase()})#end); +#elseif (${command.getProperty("Requires").getValue()} == "None") + explicit #class($command.name)(); #else - #class($command.name)(); + explicit #class($command.name)(#class(${command.getProperty("Requires").getValue()})* #variable(${command.getProperty("Requires").getValue().toLowerCase()})); #end diff --git a/src/main/resources/export/cpp/Command-constructor-variables.h b/src/main/resources/export/cpp/Command-constructor-variables.h index 9e46e70e..2f6a7c84 100644 --- a/src/main/resources/export/cpp/Command-constructor-variables.h +++ b/src/main/resources/export/cpp/Command-constructor-variables.h @@ -9,3 +9,16 @@ ## generates Foo m_foo; #end #end + +#set($command = $helper.getByName($command_name, $robot)) +#set($first = 1) +#if ($command.getProperty("Requires").getValue() != "None") + #if($first) +#class(${command.getProperty("Requires").getValue()})* m_#variable(${command.getProperty("Requires").getValue().toLowerCase()}); + #set($first = 0) + #else + ## AddRequirements(Robot::#variable(${command.getProperty("Requires").getValue()})); +,#class(${command.getProperty("Requires").getValue()})* m_#variable(${command.getProperty("Requires").getValue().toLowerCase()}); +#end +#end + diff --git a/src/main/resources/export/cpp/Command-constructor.cpp b/src/main/resources/export/cpp/Command-constructor.cpp index a4b0e074..ba483bbb 100644 --- a/src/main/resources/export/cpp/Command-constructor.cpp +++ b/src/main/resources/export/cpp/Command-constructor.cpp @@ -2,22 +2,26 @@ #set($params = $command.getProperty("Parameters").getValue()) #set($len = $params.size() - 2) #set($last = $len + 1) -#macro( klass $cmd )#if( "#type($cmd)" == "" )Command#else#type($cmd)#end#end + +\#include "commands/#class($command.name).h" #if( $params.size() > 0 ) -#class($command.name)::#class($command.name)(#if( $len >= 0 )#foreach($i in [0..$len])#param_declaration_cpp($params.get($i)), #end#end#if( $last >= 0 )#param_declaration_cpp($params.get($last))#end): #klass($command)() { +#class($command.name)::#class($command.name)(#if( $len >= 0 )#foreach($i in [0..$len])#param_declaration_cpp($params.get($i)), #end#end#if( $last >= 0 )#param_declaration_cpp($params.get($last))#end#if(${command.getProperty("Requires").getValue()} != "None") ,#class(${command.getProperty("Requires").getValue()})* #variable(${command.getProperty("Requires").getValue().toLowerCase()})#end) : +#foreach($param in $params) + m_$param.getName()($param.getName()) +#end +#if(${command.getProperty("Requires").getValue()} != "None"), m_#variable(${command.getProperty("Requires").getValue().toLowerCase()})(#variable(${command.getProperty("Requires").getValue().toLowerCase()}))#end +{ +#elseif(${command.getProperty("Requires").getValue()} == "None") +#class($command.name)::#class($command.name)(){ #else -#class($command.name)::#class($command.name)(): #klass($command)() { +#class($command.name)::#class($command.name)(#class(${command.getProperty("Requires").getValue()})* #variable(${command.getProperty("Requires").getValue().toLowerCase()})) +:m_#variable(${command.getProperty("Requires").getValue().toLowerCase()})(#variable(${command.getProperty("Requires").getValue().toLowerCase()})){ #end - #foreach($param in $params) -m_$param.getName() = $param.getName(); + + // Use AddRequirements() here to declare subsystem dependencies + // eg. AddRequirements(Robot::chassis.get()); + SetName("#class($command.name)"); + #if (${command.getProperty("Requires").getValue()} != "None") + AddRequirements(m_#variable(${command.getProperty("Requires").getValue().toLowerCase()})); #end - // Use Requires() here to declare subsystem dependencies - // eg. Requires(Robot::chassis.get()); -#@autogenerated_code("requires", " ") -#parse("${exporter_path}Command-requires.cpp") -#end -#if ( $command.getProperty("Run When Disabled").getValue() ) - SetRunWhenDisabled(true); -#end -} \ No newline at end of file diff --git a/src/main/resources/export/cpp/Command-disabled.cpp b/src/main/resources/export/cpp/Command-disabled.cpp new file mode 100644 index 00000000..4b1a0ae9 --- /dev/null +++ b/src/main/resources/export/cpp/Command-disabled.cpp @@ -0,0 +1,6 @@ +#set($command = $helper.getByName($command_name, $robot)) +#if ( $command.getProperty("Run When Disabled").getValue() ) + return true; +#else + return false; +#end diff --git a/src/main/resources/export/cpp/Command-requires.cpp b/src/main/resources/export/cpp/Command-requires.cpp deleted file mode 100644 index f0401b89..00000000 --- a/src/main/resources/export/cpp/Command-requires.cpp +++ /dev/null @@ -1,4 +0,0 @@ -#set($command = $helper.getByName($command_name, $robot)) -#if ($command.getProperty("Requires").getValue() != "None") - Requires(Robot::#variable(${command.getProperty("Requires").getValue()}).get()); -#end diff --git a/src/main/resources/export/cpp/Command.cpp b/src/main/resources/export/cpp/Command.cpp index c57040d4..cb42802b 100644 --- a/src/main/resources/export/cpp/Command.cpp +++ b/src/main/resources/export/cpp/Command.cpp @@ -2,12 +2,12 @@ #set($params = $command.getProperty("Parameters").getValue()) #header() -\#include "Commands/#class($command.name).h" - #@autogenerated_code("constructor", "") #parse("${exporter_path}Command-constructor.cpp") #end +} + // Called just before this Command runs the first time void #class($command.name)::Initialize() { @@ -24,12 +24,12 @@ bool #class($command.name)::IsFinished() { } // Called once after isFinished returns true -void #class($command.name)::End() { +void #class($command.name)::End(bool interrupted) { } -// Called when another command which requires one or more of the same -// subsystems is scheduled to run -void #class($command.name)::Interrupted() { - +bool #class($command.name)::RunsWhenDisabled() const { +#@autogenerated_code("disabled", " ") +#parse("${exporter_path}Command-disabled.cpp") +#end } diff --git a/src/main/resources/export/cpp/Command.h b/src/main/resources/export/cpp/Command.h index fd2e9341..21b9110f 100644 --- a/src/main/resources/export/cpp/Command.h +++ b/src/main/resources/export/cpp/Command.h @@ -1,32 +1,33 @@ #set($command = $helper.getByName($command_name, $robot)) -#macro( klass $cmd )#if( "#type($cmd)" == "" )frc::Command#else frc::#type($cmd)#end#end +#macro( klass $cmd ) frc2::CommandHelper<#type($cmd), $cmd.name>#end #header() #pragma once -\#include "frc/commands/Command.h" -\#include "frc/commands/Subsystem.h" -\#include "Robot.h" +#@autogenerated_code("includes", " ") +#parse("${exporter_path}command-includes.h") +#end /** * * * @author ExampleAuthor */ -class #class($command.name): public #klass($command) { +class #class($command.name): public frc2::CommandHelper<#type($command), #class($command.name)> { public: #@autogenerated_code("constructor", " ") #parse("${exporter_path}Command-constructor-header.h") #end - void Initialize() override; - void Execute() override; - bool IsFinished() override; - void End() override; - void Interrupted() override; +void Initialize() override; +void Execute() override; +bool IsFinished() override; +void End(bool interrupted) override; +bool RunsWhenDisabled() const override; + private: -#@autogenerated_code("variables", " ") +#@autogenerated_code("variables", " ") #parse("${exporter_path}Command-constructor-variables.h") #end }; diff --git a/src/main/resources/export/cpp/CommandBasedRobot-autonomous.cpp b/src/main/resources/export/cpp/CommandBasedRobot-autonomous.cpp index bedcb2a9..e8762005 100644 --- a/src/main/resources/export/cpp/CommandBasedRobot-autonomous.cpp +++ b/src/main/resources/export/cpp/CommandBasedRobot-autonomous.cpp @@ -5,15 +5,11 @@ #if ($component.getBase().getType() == "Command" && $component.getProperty("Autonomous Selection").getValue()) #if( $component.getProperty("Parameter presets").getValue().isEmpty()) - chooser.AddOption("$component.getName()", new #class($component.getName())()); + chooser.AddOption("$component.getName()", new #class($component.getName())()); #else #foreach( $set in $component.getProperty("Parameter presets").getValue() ) - chooser.AddOption("$component.getName(): $set.getName()", #command_instantiation( $component.getName(), $set.getParameters() )); + chooser.AddOption("$component.getName(): $set.getName()", #command_instantiation( $component.getName(), $set.getParameters() )); #end #end #end #end - -#if($command != "None") - chooser.SetDefaultOption("$command", #command_instantiation( $command, $params)); -#end diff --git a/src/main/resources/export/cpp/CommandBasedRobot-declarations.cpp b/src/main/resources/export/cpp/CommandBasedRobot-declarations.cpp index 8ebd50a6..f29c3893 100644 --- a/src/main/resources/export/cpp/CommandBasedRobot-declarations.cpp +++ b/src/main/resources/export/cpp/CommandBasedRobot-declarations.cpp @@ -1,6 +1,6 @@ #foreach ($component in $components) #if ($helper.exportsTo("Robot", $component)) - #declaration($component) + #declaration($component) #end #end \ No newline at end of file diff --git a/src/main/resources/export/cpp/CommandBasedRobot-includes.h b/src/main/resources/export/cpp/CommandBasedRobot-includes.h index e38b95d1..ce733f89 100644 --- a/src/main/resources/export/cpp/CommandBasedRobot-includes.h +++ b/src/main/resources/export/cpp/CommandBasedRobot-includes.h @@ -1,10 +1,10 @@ #set($autonomous = $robot.getProperty("Autonomous Command").getValue()) -#if($autonomous != "None")\#include "Commands/#class($autonomous).h" +#if($autonomous != "None")\#include "commands/#class($autonomous).h" #end #foreach( $component in $components ) #if ($component.getBase().getType() == "Command" && $component.getProperty("Autonomous Selection").getValue()) -\#include "Commands/#class($component.getName()).h" +\#include "commands/#class($component.getName()).h" #end #end ${helper.getImports($robot, "Robot")} diff --git a/src/main/resources/export/cpp/CommandBasedRobot-initialization.cpp b/src/main/resources/export/cpp/CommandBasedRobot-initialization.cpp index 02bdee18..8dc3f00c 100644 --- a/src/main/resources/export/cpp/CommandBasedRobot-initialization.cpp +++ b/src/main/resources/export/cpp/CommandBasedRobot-initialization.cpp @@ -1,6 +1,5 @@ #foreach ($component in $components) #if ($helper.exportsTo("Robot", $component)) -std::shared_ptr<#class($component.name)> Robot::#variable($component.name); +#class($component.name)* m_#variable($component.name); #end #end -std::unique_ptr Robot::oi; diff --git a/src/main/resources/export/cpp/CommandBasedRobot.cpp b/src/main/resources/export/cpp/CommandBasedRobot.cpp index b261f1e9..56eff226 100644 --- a/src/main/resources/export/cpp/CommandBasedRobot.cpp +++ b/src/main/resources/export/cpp/CommandBasedRobot.cpp @@ -2,73 +2,65 @@ \#include "Robot.h" -\#include - -\#include \#include +\#include -#@autogenerated_code("initialization", " ") -#parse("${exporter_path}CommandBasedRobot-initialization.cpp") -#end - -void Robot::RobotInit() { -#@autogenerated_code("constructors", " ") -#parse("${exporter_path}CommandBasedRobot-constructors.cpp") -#end - // This MUST be here. If the OI creates Commands (which it very likely - // will), constructing it during the construction of CommandBase (from - // which commands extend), subsystems are not guaranteed to be - // yet. Thus, their Requires() statements may grab null pointers. Bad - // news. Don't move it. - oi.reset(new OI()); - - HAL_Report(HALUsageReporting::kResourceType_Framework, - HALUsageReporting::kFramework_RobotBuilder); - - // Add commands to Autonomous Sendable Chooser -#@autogenerated_code("autonomous", " ") -#parse("${exporter_path}CommandBasedRobot-autonomous.cpp") -#end - frc::SmartDashboard::PutData("Auto Modes", &chooser); -} +void Robot::RobotInit() {} /** - * This function is called when the disabled button is hit. - * You can use it to reset subsystems before shutting down. + * This function is called every robot packet, no matter the mode. Use + * this for items like diagnostics that you want to run during disabled, + * autonomous, teleoperated and test. + * + *

This runs after the mode specific periodic functions, but before + * LiveWindow and SmartDashboard integrated updating. */ -void Robot::DisabledInit(){ +void Robot::RobotPeriodic() { frc2::CommandScheduler::GetInstance().Run(); } -} +/** + * This function is called once each time the robot enters Disabled mode. You + * can use it to reset any subsystem information you want to clear when the + * robot is disabled. + */ +void Robot::DisabledInit() {} -void Robot::DisabledPeriodic() { - frc::Scheduler::GetInstance()->Run(); -} +void Robot::DisabledPeriodic() {} +/** + * This autonomous runs the autonomous command selected by your {@link + * RobotContainer} class. + */ void Robot::AutonomousInit() { - autonomousCommand = chooser.GetSelected(); - if (autonomousCommand != nullptr) - autonomousCommand->Start(); -} + m_autonomousCommand = m_container.GetAutonomousCommand(); -void Robot::AutonomousPeriodic() { - frc::Scheduler::GetInstance()->Run(); + if (m_autonomousCommand != nullptr) { + m_autonomousCommand->Schedule(); + } } +void Robot::AutonomousPeriodic() {} + 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 - // these lines or comment it out. - if (autonomousCommand != nullptr) - autonomousCommand->Cancel(); + // 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. + if (m_autonomousCommand != nullptr) { + m_autonomousCommand->Cancel(); + m_autonomousCommand = nullptr; + } } -void Robot::TeleopPeriodic() { - frc::Scheduler::GetInstance()->Run(); -} +/** + * This function is called periodically during operator control. + */ +void Robot::TeleopPeriodic() {} + +/** + * This function is called periodically during test mode. + */ +void Robot::TestPeriodic() {} #ifndef RUNNING_FRC_TESTS -int main(int argc, char** argv) { - return frc::StartRobot(); -} -#endif \ No newline at end of file +int main() { return frc::StartRobot(); } +#endif diff --git a/src/main/resources/export/cpp/CommandBasedRobot.h b/src/main/resources/export/cpp/CommandBasedRobot.h index df660408..0d5f1749 100644 --- a/src/main/resources/export/cpp/CommandBasedRobot.h +++ b/src/main/resources/export/cpp/CommandBasedRobot.h @@ -1,30 +1,27 @@ #header() #pragma once -\#include "frc/TimedRobot.h" -\#include "frc/commands/Command.h" -\#include "frc/livewindow/LiveWindow.h" -\#include "frc/smartdashboard/SendableChooser.h" +\#include +\#include -#@autogenerated_code("includes", "") -#parse("${exporter_path}CommandBasedRobot-includes.h") -#end -\#include "OI.h" +\#include "RobotContainer.h" class Robot : public frc::TimedRobot { -public: - frc::Command* autonomousCommand = nullptr; - static std::unique_ptr oi; - frc::LiveWindow *lw = frc::LiveWindow::GetInstance(); - frc::SendableChooser chooser; -#@autogenerated_code("declarations", " ") -#parse("${exporter_path}CommandBasedRobot-declarations.cpp") -#end - void RobotInit() override; - void DisabledInit() override; - void DisabledPeriodic() override; - void AutonomousInit() override; - void AutonomousPeriodic() override; - void TeleopInit() override; - void TeleopPeriodic() override; + public: + void RobotInit() override; + void RobotPeriodic() override; + void DisabledInit() override; + void DisabledPeriodic() override; + void AutonomousInit() override; + void AutonomousPeriodic() override; + void TeleopInit() override; + void TeleopPeriodic() override; + void TestPeriodic() override; + + private: + // Have it null by default so that if testing teleop it + // doesn't have undefined behavior and potentially crash. + frc2::Command* m_autonomousCommand = nullptr; + + RobotContainer m_container; }; diff --git a/src/main/resources/export/cpp/CommandGroup-constructor.cpp b/src/main/resources/export/cpp/CommandGroup-constructor.cpp deleted file mode 100644 index 4016597a..00000000 --- a/src/main/resources/export/cpp/CommandGroup-constructor.cpp +++ /dev/null @@ -1,13 +0,0 @@ -#set($command = $helper.getByName($command_name, $robot)) -#set($params = $command.getProperty("Parameters").getValue()) -#set($len = $params.size() - 2) -#set($last = $len + 1) - -#if( $params.size() > 0 ) -#class($command.name)::#class($command.name)(#if( $len >= 0 )#foreach($i in [0..$len])#param_declaration_cpp($params.get($i)), #end#end#if( $last >= 0 )#param_declaration_cpp($params.get($last))#end): CommandGroup() { -#else -#class($command.name)::#class($command.name)() { -#end -#if ( $command.getProperty("Run When Disabled").getValue() ) - SetRunWhenDisabled(true); -#end diff --git a/src/main/resources/export/cpp/CommandGroup-declarations.cpp b/src/main/resources/export/cpp/CommandGroup-declarations.cpp deleted file mode 100644 index 7b7f42e5..00000000 --- a/src/main/resources/export/cpp/CommandGroup-declarations.cpp +++ /dev/null @@ -1,5 +0,0 @@ -#set($command = $helper.getByName($command_name, $robot)) -#set($commandDescriptors = $command.getProperty("Commands").getValue()) -#foreach( $cd in $commandDescriptors ) - Add$cd.getOrder()(#command_instantiation($cd.getName(), $cd.getParameters().getValue())); -#end \ No newline at end of file diff --git a/src/main/resources/export/cpp/CommandGroup.cpp b/src/main/resources/export/cpp/CommandGroup.cpp deleted file mode 100644 index a4a93d23..00000000 --- a/src/main/resources/export/cpp/CommandGroup.cpp +++ /dev/null @@ -1,34 +0,0 @@ -#header() - -#set($command = $helper.getByName($command_name, $robot)) -#set($commandDescriptors = $command.getProperty("Commands").getValue()) - -\#include "Commands/#class($command.name).h" -#foreach( $cd in $commandDescriptors ) -\#include "Commands/#class($cd.getName()).h" -#end - - -#@autogenerated_code("constructor", "") -#parse("${exporter_path}CommandGroup-constructor.cpp") -#end ##autogenerated - // Add Commands here: - // e.g. AddSequential(new Command1()); - // AddSequential(new Command2()); - // these will run in order. - - // To run multiple commands at the same time, - // use AddParallel() - // e.g. AddParallel(new Command1()); - // AddSequential(new Command2()); - // Command1 and Command2 will run in parallel. - - // A command group will require all of the subsystems that each member - // would require. - // e.g. if Command1 requires chassis, and Command2 requires arm, - // a CommandGroup containing them would require both the chassis and the - // arm. - #@autogenerated_code("command_declarations", " ") - #parse("${exporter_path}CommandGroup-declarations.cpp") - #end ##autogenerated -} diff --git a/src/main/resources/export/cpp/CommandGroup.h b/src/main/resources/export/cpp/CommandGroup.h deleted file mode 100644 index fe795a52..00000000 --- a/src/main/resources/export/cpp/CommandGroup.h +++ /dev/null @@ -1,23 +0,0 @@ -#header() - -#set($command = $helper.getByName($command_name, $robot)) - -#pragma once - -\#include "frc/commands/CommandGroup.h" - -/** - * - * - * @author ExampleAuthor - */ -class #class($command.name): public frc::CommandGroup { -public: - -#@autogenerated_code("constructor", " ") -#parse("${exporter_path}Command-constructor-header.h") -#end - -private: - -}; diff --git a/src/main/resources/export/cpp/ConditionalCommand-constructor.cpp b/src/main/resources/export/cpp/ConditionalCommand-constructor.cpp index 6d5f039b..dccce561 100644 --- a/src/main/resources/export/cpp/ConditionalCommand-constructor.cpp +++ b/src/main/resources/export/cpp/ConditionalCommand-constructor.cpp @@ -4,7 +4,4 @@ #class($command.name)::#class($command.name)(): ConditionalCommand(new #class($onTrue), new #class($onFalse)) { -#if ( $command.getProperty("Run When Disabled").getValue() ) - SetRunWhenDisabled(true); -#end -} + diff --git a/src/main/resources/export/cpp/ConditionalCommand-includes.h b/src/main/resources/export/cpp/ConditionalCommand-includes.h index 873a3c64..61b4c10e 100644 --- a/src/main/resources/export/cpp/ConditionalCommand-includes.h +++ b/src/main/resources/export/cpp/ConditionalCommand-includes.h @@ -3,7 +3,7 @@ #set($onFalse = $command.getProperty("On False Command").getValue()) -\#include "Commands/#class($onTrue).h" -\#include "Commands/#class($onFalse).h" +\#include "commands/#class($onTrue).h" +\#include "commands/#class($onFalse).h" \#include "frc/commands/ConditionalCommand.h" diff --git a/src/main/resources/export/cpp/ConditionalCommand.cpp b/src/main/resources/export/cpp/ConditionalCommand.cpp index 162e7921..27d999f7 100644 --- a/src/main/resources/export/cpp/ConditionalCommand.cpp +++ b/src/main/resources/export/cpp/ConditionalCommand.cpp @@ -1,12 +1,14 @@ #set($command = $helper.getByName($command_name, $robot)) #header() -\#include "Commands/#class($command.name).h" +\#include "commands/#class($command.name).h" #@autogenerated_code("constructor", " ") #parse("${exporter_path}ConditionalCommand-constructor.cpp") #end +} + bool #class($command.name)::Condition(){ - return false; + return false; } diff --git a/src/main/resources/export/cpp/ExportDescription.yaml b/src/main/resources/export/cpp/ExportDescription.yaml index 18dee9ae..f5b54861 100644 --- a/src/main/resources/export/cpp/ExportDescription.yaml +++ b/src/main/resources/export/cpp/ExportDescription.yaml @@ -68,12 +68,14 @@ Instruction Names: ["Export", "Import", "Declaration", "Construction", "LiveWind Defaults: Component: Export: "RobotMap" - Declaration: "std::shared_ptr #variable($Name);" - Import: "\\#include \"frc/${ClassName}.h\"" + Declaration: "frc::${ClassName}* m_#variable($Name);" + Import: "\\#include " + Construction: " " CustomComponent: Export: "RobotMap" Import: "\\#include \"Custom/${ClassName}.h\"" - Declaration: "std::shared_ptr<${ClassName}> #variable($Name);" + Declaration: "${ClassName} m_#variable($Name);" + Construction: " " None: Export: "" Import: "" @@ -83,31 +85,34 @@ Defaults: Extra: "" Prototype: "" Function: "" - PID: "#variable($Short_Name)->PIDGet()" + PID: "#variable($Short_Name).PIDGet()" ClassName: "" AnalogInput: - Construction: "#variable($Name).reset(new frc::${ClassName}(${Input_Channel_Analog}));" - LiveWindow: "AddChild(\"$Short_Name\", #variable($Name));" - PID: "#variable($Short_Name)->GetAverageVoltage()" + Construction: " " #"#variable($Name).reset(new frc::${ClassName}(${Input_Channel_Analog}));" + Declaration: "frc::${ClassName} m_#variable($Name){${Input_Channel_Analog}};" + LiveWindow: "AddChild(\"$Short_Name\", &m_#variable($Name));" + PID: "#variable($Short_Name).GetAverageVoltage()" AnalogPotentiometer: - Construction: "#variable($Name).reset(new frc::${ClassName}(${Input_Channel_Analog}, ${Full_Range}, ${Offset}));" - LiveWindow: "AddChild(\"$Short_Name\", #variable($Name));" - PID: "#variable($Short_Name)->Get()" + Construction: " " #"#variable($Name).reset(new frc::${ClassName}(${Input_Channel_Analog}, ${Full_Range}, ${Offset}));" + Declaration: "frc::${ClassName} m_#variable($Name){${Input_Channel_Analog}, ${Full_Range}, ${Offset}};" + LiveWindow: "AddChild(\"$Short_Name\", &m_#variable($Name));" + PID: "#variable($Short_Name).Get()" DigitalInput: - Construction: "#variable($Name).reset(new frc::${ClassName}(${Input_Channel_Digital}));" - LiveWindow: "AddChild(\"$Short_Name\", #variable($Name));" + Construction: " " #"#variable($Name).reset(new frc::${ClassName}(${Input_Channel_Digital}));" + Declaration: "frc::${ClassName} m_#variable($Name){${Input_Channel_Digital}};" + LiveWindow: "AddChild(\"$Short_Name\", &m_#variable($Name));" PWMOutput: - Construction: "#variable($Name).reset(new frc::${ClassName}(${Output_Channel_PWM}));" - LiveWindow: "AddChild(\"$Short_Name\", #variable($Name));" + Construction: " " #"#variable($Name).reset(new frc::${ClassName}(${Output_Channel_PWM}));" + LiveWindow: "AddChild(\"$Short_Name\", &m_#variable($Name));" RelayOutput: - Construction: "#variable($Name).reset(new frc::${ClassName}(${Output_Channel_Relay}));" - LiveWindow: "AddChild(\"$Short_Name\", #variable($Name));" + Construction: " " #"#variable($Name).reset(new frc::${ClassName}(${Output_Channel_Relay}));" + LiveWindow: "AddChild(\"$Short_Name\", &m_#variable($Name));" AnalogOutput: - Construction: "#variable($Name).reset(new frc::${ClassName}(${Output_Channel_AnalogOutput}));" - LiveWindow: "AddChild(\"$Short_Name\", #variable($Name));" + Construction: " " #"#variable($Name).reset(new frc::${ClassName}(${Output_Channel_AnalogOutput}));" + LiveWindow: "AddChild(\"$Short_Name\", &m_#variable($Name));" SolenoidOutput: - Construction: "#variable($Name).reset(new frc::${ClassName}(${Output_PCM_Solenoid}, ${Output_Channel_Solenoid}));" - LiveWindow: "AddChild(\"$Short_Name\", #variable($Name));" + Construction: " " #"#variable($Name).reset(new frc::${ClassName}(${Output_PCM_Solenoid}, ${Output_Channel_Solenoid}));" + LiveWindow: "AddChild(\"$Short_Name\", &m_#variable($Name));" OI: Export: "OI" Declaration: "std::shared_ptr #variable($Name);" @@ -115,7 +120,7 @@ Defaults: Extra: "#if(\"$Command\" != \"None\")#variable($Name)->${When_to_Run.substring(0,1).toUpperCase()}${When_to_Run.substring(1)}(#command_instantiation($Command $Parameters));#end" Command: Export: "OI" - Import: "\\#include \"Commands/#class($Short_Name).h\"" + Import: "\\#include \"commands/#class($Short_Name).h\"" Instructions: Robot: @@ -129,146 +134,158 @@ Instructions: Subsystem: Defaults: "None" Export: "Robot" - Import: "\\#include \"Subsystems/#class($Short_Name).h\"" + Import: "\\#include \"subsystems/#class($Short_Name).h\"" Declaration: "static std::shared_ptr<#class($Short_Name)> #variable($Short_Name);" Construction: "#variable($Short_Name).reset(new #class($Short_Name)());" - ClassName: "frc::Subsystem" + ClassName: "frc2::SubsystemBase" PID Subsystem: Defaults: "None" Export: "Robot" - Import: "\\#include \"Subsystems/#class($Short_Name).h\"" + Import: "\\#include \"subsystems/#class($Short_Name).h\"" Declaration: "static std::shared_ptr<#class($Short_Name)> #variable($Short_Name);" - Construction: "#variable($Short_Name).reset(new #class($Short_Name)());" + Construction: "" ##"#variable($Short_Name).reset(new #class($Short_Name)());" PID Controller: Defaults: "Component,None" + Import: "\\#include " ClassName: "PIDController" - Construction: "#variable($Name).reset(new frc::${ClassName}($P, $I, $D,/* F: $F, */ #variable($Input).get(), #variable($Output).get(), $Period));" + Declaration: "frc2::${ClassName} m_#variable($Name){$P, $I, $D};" Extra: > - #variable($Name)->SetContinuous(${Continuous}); - #variable($Name)->SetAbsoluteTolerance(${Tolerance}); - #if($Limit_Input) - - #variable($Name)->SetInputRange(${Minimum_Input}, ${Maximum_Input});#end - #if(true) - - #variable($Name)->SetOutputRange(${Minimum_Output}, ${Maximum_Output});#end + #if($Continuous) + m_#variable($Short_Name).EnableContinuousInput(${Minimum_Input}, ${Maximum_Input}); + #end + m_#variable($Name).SetTolerance(${Tolerance}); #if($Send_to_SmartDashboard) - SmartDashboard::PutData("${Name}", #variable($Name).get());#end + frc::SmartDashboard::PutData("${Name}", &m_#variable($Name));#end - LiveWindow: "AddChild(\"$Short_Name\", #variable($Name));" + LiveWindow: "AddChild(\"$Short_Name\", &m_#variable($Name));" Robot Drive 2: Defaults: "Component,None" ClassName: "RobotDrive" + Declaration: "frc::${ClassName} m_#variable($Name){m_#variable($Left_Motor), m_#variable($Right_Motor)};" Construction: "#variable($Name).reset(new frc::${ClassName}(#variable($Left_Motor), #variable($Right_Motor)));" Extra: > - #variable($Name)->SetSafetyEnabled($Safety_Enabled); - #variable($Name)->SetExpiration($Safety_Expiration_Time); - #variable($Name)->SetSensitivity($Sensitivity); - #variable($Name)->SetMaxOutput($Maximum_Output); + m_#variable($Name).SetSafetyEnabled($Safety_Enabled); + m_#variable($Name).SetExpiration($Safety_Expiration_Time); + m_#variable($Name).SetSensitivity($Sensitivity); + m_#variable($Name).SetMaxOutput($Maximum_Output); #if($Left_Motor_Inverted) - #variable($Name)->SetInvertedMotor(frc::RobotDrive::kRearLeftMotor, true);#end + m_#variable($Name).SetInvertedMotor(frc::RobotDrive::kRearLeftMotor, true);#end #if($Right_Motor_Inverted) - #variable($Name)->SetInvertedMotor(frc::RobotDrive::kRearRightMotor, true);#end + m_#variable($Name).SetInvertedMotor(frc::RobotDrive::kRearRightMotor, true);#end Robot Drive 4: Defaults: "Component,None" ClassName: "RobotDrive" + Declaration: "frc::${ClassName} m_#variable($Name){m_#variable($Left_Front_Motor), m_#variable($Left_Rear_Motor), + m_#variable($Right_Front_Motor), m_#variable($Right_Rear_Motor)};" Construction: >- #variable($Name).reset(new frc::${ClassName}(#variable($Left_Front_Motor), #variable($Left_Rear_Motor), #variable($Right_Front_Motor), #variable($Right_Rear_Motor))); Extra: > - #variable($Name)->SetSafetyEnabled($Safety_Enabled); - #variable($Name)->SetExpiration($Safety_Expiration_Time); - #variable($Name)->SetSensitivity($Sensitivity); - #variable($Name)->SetMaxOutput($Maximum_Output); + m_#variable($Name).SetSafetyEnabled($Safety_Enabled); + m_#variable($Name).SetExpiration($Safety_Expiration_Time); + m_#variable($Name).SetSensitivity($Sensitivity); + m_#variable($Name).SetMaxOutput($Maximum_Output); #if($Left_Front_Motor_Inverted) - #variable($Name)->SetInvertedMotor(frc::RobotDrive::kFrontLeftMotor, true);#end + m_#variable($Name).SetInvertedMotor(frc::RobotDrive::kFrontLeftMotor, true);#end #if($Left_Rear_Motor_Inverted) - #variable($Name)->SetInvertedMotor(frc::RobotDrive::kRearLeftMotor, true);#end + m_#variable($Name).SetInvertedMotor(frc::RobotDrive::kRearLeftMotor, true);#end #if($Right_Front_Motor_Inverted) - #variable($Name)->SetInvertedMotor(frc::RobotDrive::kFrontRightMotor, true);#end + m_#variable($Name).SetInvertedMotor(frc::RobotDrive::kFrontRightMotor, true);#end #if($Right_Rear_Motor_Inverted) - #variable($Name)->SetInvertedMotor(frc::RobotDrive::kRearRightMotor, true);#end + m_#variable($Name).SetInvertedMotor(frc::RobotDrive::kRearRightMotor, true);#end Speed Controller Group: Defaults: "Component,None" ClassName: "SpeedControllerGroup" - LiveWindow: "AddChild(\"$Short_Name\", #variable($Name));" + Declaration: "frc::${ClassName} m_#variable($Name){m_#variable($SpeedController1), m_#variable($SpeedController2) + #if(($SpeedController3)), m_#variable($SpeedController3)#end #if(($SpeedController4)), m_#variable($SpeedController4)#end};" + LiveWindow: "AddChild(\"$Short_Name\", &m_#variable($Name));" Construction: >- #variable($Name) = std::make_shared(*#variable($SpeedController1), *#variable($SpeedController2) #if(($SpeedController3)), *#variable($SpeedController3)#end #if(($SpeedController4)), *#variable($SpeedController4)#end); Differential Drive: Defaults: "Component,None" ClassName: "DifferentialDrive" + Declaration: "frc::${ClassName} m_#variable($Name){m_#variable($Left_Motor), m_#variable($Right_Motor)};" Construction: "#variable($Name).reset(new frc::${ClassName}(*#variable($Left_Motor), *#variable($Right_Motor)));" - LiveWindow: "AddChild(\"$Short_Name\", #variable($Name));" - Import: "\\#include \"frc/drive/${ClassName}.h\"" + LiveWindow: "AddChild(\"$Short_Name\", &m_#variable($Name));" + Import: "\\#include " Extra: > - #variable($Name)->SetSafetyEnabled($Safety_Enabled); - #variable($Name)->SetExpiration($Safety_Expiration_Time); - #variable($Name)->SetMaxOutput($Maximum_Output); + m_#variable($Name).SetSafetyEnabled($Safety_Enabled); + m_#variable($Name).SetExpiration($Safety_Expiration_Time); + m_#variable($Name).SetMaxOutput($Maximum_Output); Mecanum Drive: Defaults: "Component,None" ClassName: "MecanumDrive" - LiveWindow: "AddChild(\"$Short_Name\", #variable($Name));" - Import: "\\#include \"frc/drive/${ClassName}.h\"" + Declaration: "frc::${ClassName} m_#variable($Name){m_#variable($Left_Front_Motor), m_#variable($Left_Rear_Motor), + m_#variable($Right_Front_Motor), m_#variable($Right_Rear_Motor)};" + LiveWindow: "AddChild(\"$Short_Name\", &m_#variable($Name));" + Import: "\\#include " Construction: >- #variable($Name).reset(new frc::${ClassName}(*#variable($Left_Front_Motor), *#variable($Left_Rear_Motor), *#variable($Right_Front_Motor), *#variable($Right_Rear_Motor))); Extra: > - #variable($Name)->SetSafetyEnabled($Safety_Enabled); - #variable($Name)->SetExpiration($Safety_Expiration_Time); - #variable($Name)->SetMaxOutput($Maximum_Output); + m_#variable($Name).SetSafetyEnabled($Safety_Enabled); + m_#variable($Name).SetExpiration($Safety_Expiration_Time); + m_#variable($Name).SetMaxOutput($Maximum_Output); Killough Drive: Defaults: "Component,None" ClassName: "KilloughDrive" - LiveWindow: "AddChild(\"$Short_Name\", #variable($Name));" - Import: "\\#include \"frc/drive/${ClassName}.h\"" + Declaration: "frc::${ClassName} m_#variable($Name){m_#variable($Left_Motor), m_#variable($Right_Motor), + m_#variable($Back_Motor)};" + LiveWindow: "AddChild(\"$Short_Name\", &m_#variable($Name));" + Import: "\\#include " Construction: >- #variable($Name).reset(new frc::${ClassName}(*#variable($Left_Motor), *#variable($Right_Motor), *#variable($Back_Motor))); Extra: > - #variable($Name)->SetSafetyEnabled($Safety_Enabled); - #variable($Name)->SetExpiration($Safety_Expiration_Time); - #variable($Name)->SetMaxOutput($Maximum_Output); + m_#variable($Name).SetSafetyEnabled($Safety_Enabled); + m_#variable($Name).SetExpiration($Safety_Expiration_Time); + m_#variable($Name).SetMaxOutput($Maximum_Output); AnalogGyro: Defaults: "AnalogInput,Component,None" + Declaration: "frc::${ClassName} m_#variable($Name){${Input_Channel_Analog}};" ClassName: "AnalogGyro" - Extra: "#variable($Name)->SetSensitivity(${Sensitivity});" - PID: "#variable($Short_Name)->PIDGet()" + Extra: "m_#variable($Name).SetSensitivity(${Sensitivity});" + PID: "m_#variable($Short_Name).PIDGet()" AnalogAccelerometer: Defaults: "AnalogInput,Component,None" + Declaration: "frc::${ClassName} m_#variable($Name){${Input_Channel_Analog}};" ClassName: "AnalogAccelerometer" - PID: "#variable($Short_Name)->GetAcceleration()" + PID: "#variable($Short_Name).GetAcceleration()" Extra: >- - #variable($Name)->SetSensitivity(${Volts_Per_G}); - #variable($Name)->SetZero(${Zero_G_Volts}); + m_#variable($Name).SetSensitivity(${Volts_Per_G}); + m_#variable($Name).SetZero(${Zero_G_Volts}); Quadrature Encoder: Defaults: "DigitalInput,Component,None" ClassName: "Encoder" - Construction: "#variable($Name).reset(new frc::${ClassName}(${Channel_A_Channel_Digital}, ${Channel_B_Channel_Digital}, ${Reverse_Direction}, frc::Encoder::${Encoding_Type}));" + Declaration: "frc::Encoder m_#variable($Name){${Channel_A_Channel_Digital}, ${Channel_B_Channel_Digital}, ${Reverse_Direction}, frc::Encoder::${Encoding_Type}};" + Construction: "" #"#variable($Name).reset(new frc::${ClassName}(${Channel_A_Channel_Digital}, ${Channel_B_Channel_Digital}, ${Reverse_Direction}, frc::Encoder::${Encoding_Type}));" Extra: >- - #variable($Name)->SetDistancePerPulse(${Distance_Per_Pulse}); - #variable($Name)->SetPIDSourceType(frc::PIDSourceType::${PID_Source}); + m_#variable($Name).SetDistancePerPulse(${Distance_Per_Pulse}); + m_#variable($Name).SetPIDSourceType(frc::PIDSourceType::${PID_Source}); Indexed Encoder: Defaults: "DigitalInput,Component,None" ClassName: "Encoder" - Construction: "#variable($Name).reset(new frc::${ClassName}(${Channel_A_Channel_Digital}, ${Channel_B_Channel_Digital}, ${Reverse_Direction}));" + Declaration: "frc::Encoder m_#variable($Name){${Channel_A_Channel_Digital}, ${Channel_B_Channel_Digital}, ${Reverse_Direction}};" + Construction: "" #"#variable($Name).reset(new frc::${ClassName}(${Channel_A_Channel_Digital}, ${Channel_B_Channel_Digital}, ${Reverse_Direction}));" Extra: >- - #variable($Name)->SetDistancePerPulse(${Distance_Per_Pulse}); - #variable($Name)->SetPIDSourceType(frc::PIDSourceType::${PID_Source}); - #variable($Name)->SetIndexSource((unsigned int)${Index_Channel_Digital}, frc::Encoder::IndexingType::${Indexing_Type}); + m_#variable($Name).SetDistancePerPulse(${Distance_Per_Pulse}); + m_#variable($Name).SetPIDSourceType(frc::PIDSourceType::${PID_Source}); + m_#variable($Name).SetIndexSource((unsigned int)${Index_Channel_Digital}, frc::Encoder::IndexingType::${Indexing_Type}); Gear Tooth Sensor: Defaults: "DigitalInput,Component,None" ClassName: "GearTooth" + Declaration: "frc::GearTooth m_#variable($Name){${Input_Channel_Digital}, ${Direction_Sensitive}};" Construction: "#variable($Name).reset(new frc::${ClassName}(${Input_Channel_Digital}, ${Direction_Sensitive}));" Analog Potentiometer: Defaults: "AnalogPotentiometer,Component,None" @@ -285,51 +302,62 @@ Instructions: Ultrasonic: Defaults: "DigitalInput,Component,None" ClassName: "Ultrasonic" - Construction: "#variable($Name).reset(new frc::${ClassName}(${Ping_Channel_Digital}, ${Echo_Channel_Digital}));" + Declaration: "frc::Ultrasonic m_#variable($Name){${Ping_Channel_Digital}, ${Echo_Channel_Digital}};" + Construction: "" #"#variable($Name).reset(new frc::${ClassName}(${Ping_Channel_Digital}, ${Echo_Channel_Digital}));" PowerDistributionPanel: Defaults: "Component,None" ClassName: "PowerDistributionPanel" - Construction: "#variable($Name).reset(new frc::${ClassName}($CAN_ID));" - LiveWindow: "AddChild(\"$Short_Name\", #variable($Name));" + Declaration: "frc::PowerDistributionPanel m_#variable($Name){$CAN_ID};" + Construction: "" #"#variable($Name).reset(new frc::${ClassName}($CAN_ID));" + LiveWindow: "AddChild(\"$Short_Name\", &m_#variable($Name));" Speed Controller: Defaults: "PWMOutput,Component,None" ClassName: "SpeedController" - Construction: "#variable($Name).reset(new frc::${Type}(${Output_Channel_PWM}));" - LiveWindow: "AddChild(\"$Short_Name\", std::static_pointer_cast(#variable($Name)));" -# Import: "\\#include \"frc/${Type}.h\"\\n\\#include \"frc/${ClassName}.h";" - Import: "\\#include \"frc/${Type}.h\"" + Declaration: "frc::${Type} m_#variable($Name){${Output_Channel_PWM}};" + Construction: " " #"#variable($Name).reset(new frc::${Type}(${Output_Channel_PWM}));" + LiveWindow: "AddChild(\"$Short_Name\", &m_#variable($Name));" + Import: "\\#include " Nidec Brushless: Defaults: "Component,None" ClassName: "NidecBrushless" - Construction: "#variable($Name).reset(new frc::${ClassName}(${Output_Channel_PWM}, ${Output_Channel_Digital}));" - LiveWindow: "AddChild(\"$Short_Name\", #variable($Name));" + Declaration: "frc::${ClassName} m_#variable($Name){${Output_Channel_PWM}, ${Output_Channel_Digital}};" + Construction: " " #"#variable($Name).reset(new frc::${ClassName}(${Output_Channel_PWM}, ${Output_Channel_Digital}));" + LiveWindow: "AddChild(\"$Short_Name\", &m_#variable($Name));" Servo: Defaults: "PWMOutput,Component,None" ClassName: "Servo" + Declaration: "frc::${ClassName} m_#variable($Name){${Output_Channel_PWM}};" Digital Output: Defaults: "Component,None" ClassName: "DigitalOutput" - Construction: "#variable($Name).reset(new frc::${ClassName}(${Output_Channel_Digital}));" - LiveWindow: "AddChild(\"$Short_Name\", #variable($Name));" + Declaration: "frc::${ClassName} m_#variable($Name){${Output_Channel_Digital}};" + Construction: " " #"#variable($Name).reset(new frc::${ClassName}(${Output_Channel_Digital}));" + LiveWindow: "AddChild(\"$Short_Name\", &m_#variable($Name));" Spike: Defaults: "RelayOutput,Component,None" ClassName: "Relay" + Declaration: "frc::${ClassName} m_#variable($Name){${Output_Channel_Relay}};" Analog Output: Defaults: "AnalogOutput,Component,None" ClassName: "AnalogOutput" + Declaration: "frc::${ClassName} m_#variable($Name){${Output_Channel_AnalogOutput}};" Compressor: Defaults: "Component,None" ClassName: "Compressor" - Construction: "#variable($Name).reset(new frc::${ClassName}(${PCM_ID}));" - LiveWindow: "AddChild(\"$Short_Name\", #variable($Name));" + Declaration: "frc::Compressor m_#variable($Name){${PCM_ID}};" + Construction: "" # "#variable($Name).reset(new frc::${ClassName}(${PCM_ID}));" + LiveWindow: "AddChild(\"$Short_Name\", &m_#variable($Name));" Solenoid: Defaults: "SolenoidOutput,Component,None" ClassName: "Solenoid" + Declaration: "frc::Solenoid m_#variable($Name){${Output_PCM_Solenoid}, ${Output_Channel_Solenoid}};" Relay Solenoid: Defaults: "RelayOutput,Component,None" ClassName: "Relay" + Declaration: "frc::Relay m_#variable($Name){${Output_Channel_Relay}};" + Double Solenoid: Defaults: "Solenoid,Component,None" ClassName: "DoubleSolenoid" @@ -337,28 +365,29 @@ Instructions: #if(${Forward_PCM_Solenoid} != ${Reverse_PCM_Solenoid})Warning, the two modules in robot builder are different! #end## + # #variable($Name).reset(new frc::${ClassName}(${Forward_PCM_Solenoid}, ${Forward_Channel_Solenoid}, ${Reverse_Channel_Solenoid})); - #variable($Name).reset(new frc::${ClassName}(${Forward_PCM_Solenoid}, ${Forward_Channel_Solenoid}, ${Reverse_Channel_Solenoid})); - LiveWindow: "AddChild(\"$Short_Name\", #variable($Name));" + Declaration: "frc::DoubleSolenoid m_#variable($Name){${Forward_PCM_Solenoid}, ${Forward_Channel_Solenoid}, ${Reverse_Channel_Solenoid}};" + LiveWindow: "AddChild(\"$Short_Name\", &m_#variable($Name));" Joystick: Defaults: "OI,None" ClassName: "Joystick" - Construction: "#variable($Name).reset(new frc::${ClassName}(${Number}));" - Prototype: "std::shared_ptr get#class($Name)();" - Function: >- - std::shared_ptr OI::get#class($Name)() { - return #variable($Name); - } + Construction: "frc::${ClassName} m_#variable($Name){${Number}};" + # Prototype: "std::shared_ptr get#class($Name)();" + #Function: >- + # std::shared_ptr OI::get#class($Name)() { + # return #variable($Name); + # } Joystick Button: Defaults: "Button,OI,None" ClassName: "JoystickButton" - Construction: "#variable($Name).reset(new frc::${ClassName}(#variable($Joystick).get(), ${Button}));" + Construction: "frc2::${ClassName} m_#variable($Name){&m_#variable($Joystick), ${Button}};" Command: Defaults: "Command,None" - ClassName: "frc::Command" - Command Group: + ClassName: "frc2::CommandBase" + Sequential Command Group: Defaults: "Command,None" PID Command: Defaults: "Command,None" diff --git a/src/main/resources/export/cpp/InstantCommand-constructor.cpp b/src/main/resources/export/cpp/InstantCommand-constructor.cpp index ac61123a..a432ddb2 100644 --- a/src/main/resources/export/cpp/InstantCommand-constructor.cpp +++ b/src/main/resources/export/cpp/InstantCommand-constructor.cpp @@ -6,17 +6,14 @@ #if( $params.size() > 0 ) #class($command.name)::#class($command.name)(#if( $len >= 0 )#foreach($i in [0..$len])#param_declaration_cpp($params.get($i)), #end#end#if( $last >= 0 )#param_declaration_cpp($params.get($last))#end): InstantCommand() { #else -#class($command.name)::#class($command.name)(): InstantCommand() { +#class($command.name)::#class($command.name)(#class(${command.getProperty("Requires").getValue()})* #variable(${command.getProperty("Requires").getValue().toLowerCase()})): InstantCommand() { #end #foreach($param in $params) m_$param.getName() = $param.getName(); #end - // Use Requires() here to declare subsystem dependencies - // eg. Requires(Robot::chassis.get()); -#@autogenerated_code("requires", " ") -#parse("${exporter_path}Command-requires.cpp") -#end -#if ( $command.getProperty("Run When Disabled").getValue() ) - SetRunWhenDisabled(true); -#end -} + // Use AddRequirements() here to declare subsystem dependencies + // eg. AddRequirements(Robot::chassis.get()); + SetName("#class($command.name)"); + #if (${command.getProperty("Requires").getValue()} != "None") + AddRequirements(m_#variable(${command.getProperty("Requires").getValue().toLowerCase()})); + #end \ No newline at end of file diff --git a/src/main/resources/export/cpp/InstantCommand.cpp b/src/main/resources/export/cpp/InstantCommand.cpp index 1e28a9a9..7ef2e938 100644 --- a/src/main/resources/export/cpp/InstantCommand.cpp +++ b/src/main/resources/export/cpp/InstantCommand.cpp @@ -2,12 +2,14 @@ #set($params = $command.getProperty("Parameters").getValue()) #header() -\#include "Commands/#class($command.name).h" +\#include "commands/#class($command.name).h" #@autogenerated_code("constructor", "") #parse("${exporter_path}InstantCommand-constructor.cpp") #end +} + // Called once when this command runs void #class($command.name)::Initialize() { diff --git a/src/main/resources/export/cpp/InstantCommand.h b/src/main/resources/export/cpp/InstantCommand.h index 0ccdfaa8..9aa327b6 100644 --- a/src/main/resources/export/cpp/InstantCommand.h +++ b/src/main/resources/export/cpp/InstantCommand.h @@ -3,25 +3,24 @@ #pragma once -\#include "frc/commands/InstantCommand.h" -\#include "frc/commands/Subsystem.h" -\#include "Robot.h" +\#include "frc2/command/InstantCommand.h" +\#include "subsystems/#class(${command.getProperty("Requires").getValue()}).h" /** * * * @author ExampleAuthor */ -class #class($command.name): public frc::InstantCommand { +class #class($command.name): public frc2::InstantCommand { public: #@autogenerated_code("constructor", " ") #parse("${exporter_path}Command-constructor-header.h") #end - void Initialize() override; + void Initialize() override; private: -#@autogenerated_code("variables", " ") +#@autogenerated_code("variables", " ") #parse("${exporter_path}Command-constructor-variables.h") #end }; diff --git a/src/main/resources/export/cpp/OI-constructors.cpp b/src/main/resources/export/cpp/OI-constructors.cpp deleted file mode 100644 index 12f6fbbd..00000000 --- a/src/main/resources/export/cpp/OI-constructors.cpp +++ /dev/null @@ -1,25 +0,0 @@ -##${Collections.reverse($components)} -#foreach( $component in $components ) -#if ($helper.exportsTo("OI", $component) - && ("#constructor($component)" != "" || "#extra($component)" != "")) - #constructor($component) - - #extra($component) - -#end -#end - -##${Collections.reverse($components)} - // SmartDashboard Buttons -#foreach( $component in $components ) -#if ($component.getBase().getType() == "Command" - && $component.getProperty("Button on SmartDashboard").getValue()) -#if( $component.getProperty("Parameter presets").getValue().isEmpty()) - frc::SmartDashboard::PutData("$component.getName()", new #class($component.getName())()); -#else -#foreach( $set in $component.getProperty("Parameter presets").getValue() ) - frc::SmartDashboard::PutData("$component.getName(): $set.getName()", #command_instantiation( $component.getName(), $set.getParameters() )); -#end -#end -#end -#end diff --git a/src/main/resources/export/cpp/OI-declarations.h b/src/main/resources/export/cpp/OI-declarations.h deleted file mode 100644 index 7b92e319..00000000 --- a/src/main/resources/export/cpp/OI-declarations.h +++ /dev/null @@ -1,7 +0,0 @@ -#foreach ($component in $components) -#if ($helper.exportsTo("OI", $component) - && "#type($component)" != "" ) - #declaration($component) - -#end -#end diff --git a/src/main/resources/export/cpp/OI-includes.h b/src/main/resources/export/cpp/OI-includes.h deleted file mode 100644 index 7935a9fa..00000000 --- a/src/main/resources/export/cpp/OI-includes.h +++ /dev/null @@ -1,2 +0,0 @@ -\#include "frc/smartdashboard/SmartDashboard.h" -${helper.getImports($robot, "OI")} diff --git a/src/main/resources/export/cpp/OI-prototypes.h b/src/main/resources/export/cpp/OI-prototypes.h deleted file mode 100644 index d43706e0..00000000 --- a/src/main/resources/export/cpp/OI-prototypes.h +++ /dev/null @@ -1,8 +0,0 @@ -${Collections.reverse($components)} -#foreach( $component in $components ) -#if ($helper.exportsTo("OI", $component) - && "#prototype($component)" != "") - #prototype($component) - -#end -#end diff --git a/src/main/resources/export/cpp/OI.cpp b/src/main/resources/export/cpp/OI.cpp deleted file mode 100644 index c2688e8f..00000000 --- a/src/main/resources/export/cpp/OI.cpp +++ /dev/null @@ -1,18 +0,0 @@ -#header() - -\#include "OI.h" - -#@autogenerated_code("includes", "") -#parse("${exporter_path}OI-includes.h") -#end - -OI::OI() { - // Process operator interface input here. -#@autogenerated_code("constructors", " ") -#parse("${exporter_path}OI-constructors.cpp") -#end -} - -#@autogenerated_code("functions", "") -#parse("${exporter_path}OI-functions.cpp") -#end diff --git a/src/main/resources/export/cpp/OI.h b/src/main/resources/export/cpp/OI.h deleted file mode 100644 index 471396dd..00000000 --- a/src/main/resources/export/cpp/OI.h +++ /dev/null @@ -1,20 +0,0 @@ -#header() - -#pragma once - -\#include "frc/Joystick.h" -\#include "frc/buttons/JoystickButton.h" - -class OI { -private: -#@autogenerated_code("declarations", " ") -#parse("${exporter_path}OI-declarations.h") -#end -public: - OI(); - -#@autogenerated_code("prototypes", " ") -#parse("${exporter_path}OI-prototypes.h") -#end -}; - diff --git a/src/main/resources/export/cpp/PIDCommand-constructor.cpp b/src/main/resources/export/cpp/PIDCommand-constructor.cpp index 60f9c4ec..2ef4359d 100644 --- a/src/main/resources/export/cpp/PIDCommand-constructor.cpp +++ b/src/main/resources/export/cpp/PIDCommand-constructor.cpp @@ -3,21 +3,41 @@ #set($len = $params.size() - 2) #set($last = $len + 1) +#set($command = $helper.getByName($command_name, $robot)) +#set($actuator = $command.getProperty("Output").getValue()) +#set($subsystem = $command.getProperty("Requires").getValue()) +#foreach ($component in $components) +#if ($component.name == $actuator) +#set($Output = $component.name) +#end +#end + +#set($command = $helper.getByName($command_name, $robot)) +#set($sensor = $command.getProperty("Input").getValue()) +#set($subsystem = $command.getProperty("Requires").getValue()) +#foreach ($component in $components) +#if ($component.name == $sensor) +#set($Input = $component.name) +#end +#end + #if( $params.size() > 0 ) #class($command.name)::#class($command.name)(#if( $len >= 0 )#foreach($i in [0..$len])#param_declaration_cpp($params.get($i)), #end#end#if( $last >= 0 )#param_declaration_cpp($params.get($last))#end): #klass($command)() { #else -#class($command.name)::#class($command.name)(): frc::PIDCommand("#class($command_name)", ${command.getProperty("P").getValue()}, ${command.getProperty("I").getValue()}, ${command.getProperty("D").getValue()}, ${command.getProperty("Period").getValue()}) { - { +#class($command.name)::#class($command.name)(#class(${command.getProperty("Requires").getValue()})* #variable(${command.getProperty("Requires").getValue().toLowerCase()})): frc2::CommandHelper( +frc2::PIDController(double(${command.getProperty("P").getValue()}), double(${command.getProperty("I").getValue()}), double(${command.getProperty("D").getValue()})), +[this](){return m_#variable(${command.getProperty("Requires").getValue().toLowerCase()})-> Get#class($Input)().PIDGet();}, +0, [this](double output){m_#variable(${command.getProperty("Requires").getValue().toLowerCase()})-> Get#class($Output)().PIDWrite(output);}, +{#variable(${command.getProperty("Requires").getValue().toLowerCase()})}), +m_#variable(${command.getProperty("Requires").getValue().toLowerCase()}) (#variable(${command.getProperty("Requires").getValue().toLowerCase()})){ +m_controller.SetTolerance(${command.getProperty("Tolerance").getValue()}); #end #foreach($param in $params) -m_$param.getName() = $param.getName(); + m_$param.getName() = $param.getName(); + #end + // Use AddRequirements() here to declare subsystem dependencies + // eg. AddRequirements(Robot::chassis.get()); + SetName("#class($command.name)"); + #if (${command.getProperty("Requires").getValue()} != "None") + AddRequirements(m_#variable(${command.getProperty("Requires").getValue().toLowerCase()})); #end - // Use Requires() here to declare subsystem dependencies - // eg. Requires(Robot::chassis.get()); -#@autogenerated_code("requires", " ") -#parse("${exporter_path}Command-requires.cpp") -#end -#if ( $command.getProperty("Run When Disabled").getValue() ) - SetRunWhenDisabled(true); -#end -} \ No newline at end of file diff --git a/src/main/resources/export/cpp/PIDCommand-includes.h b/src/main/resources/export/cpp/PIDCommand-includes.h new file mode 100644 index 00000000..602eb39b --- /dev/null +++ b/src/main/resources/export/cpp/PIDCommand-includes.h @@ -0,0 +1,4 @@ + +\#include "frc2/Command/PIDCommand.h" +\#include +\#include "subsystems/#class(${command.getProperty("Requires").getValue()}).h" \ No newline at end of file diff --git a/src/main/resources/export/cpp/PIDCommand-output.cpp b/src/main/resources/export/cpp/PIDCommand-output.cpp index 844cad4c..285f03fe 100644 --- a/src/main/resources/export/cpp/PIDCommand-output.cpp +++ b/src/main/resources/export/cpp/PIDCommand-output.cpp @@ -3,6 +3,6 @@ #set($subsystem = $command.getProperty("Requires").getValue()) #foreach ($component in $components) #if ($component.name == $actuator) - Robot::#variable($subsystem)->Get#class($component.name)()->PIDWrite(output); + m_#variable($subsystem)->Get#class($component.name)().PIDWrite(output); #end #end \ No newline at end of file diff --git a/src/main/resources/export/cpp/PIDCommand-pid.cpp b/src/main/resources/export/cpp/PIDCommand-pid.cpp index 549ac270..f3f98421 100644 --- a/src/main/resources/export/cpp/PIDCommand-pid.cpp +++ b/src/main/resources/export/cpp/PIDCommand-pid.cpp @@ -1,9 +1,9 @@ #set($command = $helper.getByName($command_name, $robot)) - GetPIDController()->SetContinuous(${command.getProperty("Continuous").getValue()}); - GetPIDController()->SetAbsoluteTolerance(${command.getProperty("Tolerance").getValue()}); + // GetPIDController()->SetContinuous(${command.getProperty("Continuous").getValue()}); + // GetPIDController()->SetAbsoluteTolerance(${command.getProperty("Tolerance").getValue()}); #if($command.getProperty("Limit Input").getValue()) - GetPIDController()->SetInputRange(${command.getProperty("Minimum Input").getValue()}, ${command.getProperty("Maximum Input").getValue()}); + // GetPIDController()->SetInputRange(${command.getProperty("Minimum Input").getValue()}, ${command.getProperty("Maximum Input").getValue()}); #end #if($command.getProperty("Limit Output").getValue()) - GetPIDController()->SetOutputRange(${command.getProperty("Minimum Output").getValue()}, ${command.getProperty("Maximum Output").getValue()}); + // GetPIDController()->SetOutputRange(${command.getProperty("Minimum Output").getValue()}, ${command.getProperty("Maximum Output").getValue()}); #end diff --git a/src/main/resources/export/cpp/PIDCommand-source.cpp b/src/main/resources/export/cpp/PIDCommand-source.cpp index cdc22f11..9e85fecd 100644 --- a/src/main/resources/export/cpp/PIDCommand-source.cpp +++ b/src/main/resources/export/cpp/PIDCommand-source.cpp @@ -3,6 +3,6 @@ #set($subsystem = $command.getProperty("Requires").getValue()) #foreach ($component in $components) #if ($component.name == $sensor) - return Robot::#variable($subsystem)->Get#class($component.name)()->PIDGet(); + return m_#variable($subsystem)->Get#class($component.name)().PIDGet(); #end #end diff --git a/src/main/resources/export/cpp/PIDCommand.cpp b/src/main/resources/export/cpp/PIDCommand.cpp index afc5b12e..ab68e4c1 100644 --- a/src/main/resources/export/cpp/PIDCommand.cpp +++ b/src/main/resources/export/cpp/PIDCommand.cpp @@ -2,21 +2,20 @@ #set($params = $command.getProperty("Parameters").getValue()) #header() -\#include "Commands/#class($command.name).h" - +\#include "commands/#class($command.name).h" +\#include "frc/controller/PIDController.h" +\#include #@autogenerated_code("constructor", " ") #parse("${exporter_path}PIDCommand-constructor.cpp") #end + +} + #@autogenerated_code("pid", " ") #parse("${exporter_path}PIDCommand-pid.cpp") #end - // Use Requires() here to declare subsystem dependencies - // eg. Requires(chassis); -#@autogenerated_code("requires", " ") -#parse("${exporter_path}Command-requires.cpp") -#end -} + double #class($command.name)::ReturnPIDInput() { // Return your input value for the PID loop diff --git a/src/main/resources/export/cpp/PIDCommand.h b/src/main/resources/export/cpp/PIDCommand.h index fd502b89..9d997d1c 100644 --- a/src/main/resources/export/cpp/PIDCommand.h +++ b/src/main/resources/export/cpp/PIDCommand.h @@ -4,34 +4,34 @@ #pragma once -\#include "frc/commands/PIDCommand.h" -\#include "frc/commands/Subsystem.h" -\#include "Robot.h" +#@autogenerated_code("constructor", " ") +#parse("${exporter_path}PIDCommand-includes.h") +#end /** * * * @author ExampleAuthor */ -class #class($command.name): public frc::PIDCommand { +class #class($command.name): public frc2::CommandHelper { public: #@autogenerated_code("constructor", " ") #parse("${exporter_path}Command-constructor-header.h") #end - double ReturnPIDInput() override; - void UsePIDOutput(double output) override; - void Initialize() override; - void Execute() override; - bool IsFinished() override; - void End() override; - void Interrupted() override; + double ReturnPIDInput(); + void UsePIDOutput(double output); + void Initialize(); + void Execute(); + bool IsFinished(); + void End(); + void Interrupted(); -#@autogenerated_code("cmdpidgetters"," ") +#@autogenerated_code("cmdpidgetters"," ") #parse("${exporter_path}Subsystem-pidgetters.h") #end private: -#@autogenerated_code("variables", " ") +#@autogenerated_code("variables", " ") #parse("${exporter_path}Command-constructor-variables.h") #end }; diff --git a/src/main/resources/export/cpp/PIDSubsystem-output.cpp b/src/main/resources/export/cpp/PIDSubsystem-output.cpp index c079bb43..de037185 100644 --- a/src/main/resources/export/cpp/PIDSubsystem-output.cpp +++ b/src/main/resources/export/cpp/PIDSubsystem-output.cpp @@ -1,6 +1,6 @@ #set($subsystem = $helper.getByName($subsystem_name, $robot)) #foreach ($component in $components) #if ($component.name == $subsystem.getProperty("Output").getValue()) - #variable($component.name)->PIDWrite(output); + m_#variable($component.name).PIDWrite(output); #end #end \ No newline at end of file diff --git a/src/main/resources/export/cpp/PIDSubsystem-pid.cpp b/src/main/resources/export/cpp/PIDSubsystem-pid.cpp index adf376d8..cdd57a8e 100644 --- a/src/main/resources/export/cpp/PIDSubsystem-pid.cpp +++ b/src/main/resources/export/cpp/PIDSubsystem-pid.cpp @@ -1,12 +1,10 @@ #set($subsystem = $helper.getByName($subsystem_name, $robot)) -#class($subsystem.name)::#class($subsystem.name)() : PIDSubsystem("#class($subsystem.name)", ${subsystem.getProperty("P").getValue()}, ${subsystem.getProperty("I").getValue()}, ${subsystem.getProperty("D").getValue()}) { - SetAbsoluteTolerance(${subsystem.getProperty("Tolerance").getValue()}); - GetPIDController()->SetContinuous(${subsystem.getProperty("Continuous").getValue()}); - GetPIDController()->SetName("$subsystem_name", "PIDSubsystem Controller"); - AddChild(GetPIDController()); +#class($subsystem.name)::#class($subsystem.name)() : frc2::PIDSubsystem(frc2::PIDController(${subsystem.getProperty("P").getValue()}, ${subsystem.getProperty("I").getValue()}, ${subsystem.getProperty("D").getValue()})) { + m_controller.SetTolerance(${subsystem.getProperty("Tolerance").getValue()}); + SetName("$subsystem_name"); #if($subsystem.getProperty("Limit Input").getValue()) - GetPIDController()->SetInputRange(${subsystem.getProperty("Minimum Input").getValue()}, ${subsystem.getProperty("Maximum Input").getValue()}); + GetPIDController().SetInputRange(${subsystem.getProperty("Minimum Input").getValue()}, ${subsystem.getProperty("Maximum Input").getValue()}); #end #if($subsystem.getProperty("Limit Output").getValue()) - GetPIDController()->SetOutputRange(${subsystem.getProperty("Minimum Output").getValue()}, ${subsystem.getProperty("Maximum Output").getValue()}); + GetPIDController().SetOutputRange(${subsystem.getProperty("Minimum Output").getValue()}, ${subsystem.getProperty("Maximum Output").getValue()}); #end diff --git a/src/main/resources/export/cpp/PIDSubsystem-source.cpp b/src/main/resources/export/cpp/PIDSubsystem-source.cpp index f13d6a5b..6ba8f18d 100644 --- a/src/main/resources/export/cpp/PIDSubsystem-source.cpp +++ b/src/main/resources/export/cpp/PIDSubsystem-source.cpp @@ -1,6 +1,6 @@ #set($subsystem = $helper.getByName($subsystem_name, $robot)) #foreach ($component in $components) #if ($component.name == $subsystem.getProperty("Input").getValue()) - return #pid($component); + return m_#pid($component); #end #end \ No newline at end of file diff --git a/src/main/resources/export/cpp/PIDSubsystem.cpp b/src/main/resources/export/cpp/PIDSubsystem.cpp index 8884de1d..ebd5773f 100644 --- a/src/main/resources/export/cpp/PIDSubsystem.cpp +++ b/src/main/resources/export/cpp/PIDSubsystem.cpp @@ -2,9 +2,10 @@ #set($subsystem = $helper.getByName($subsystem_name, $robot)) -\#include "Subsystems/#class($subsystem.name).h" -\#include "frc/smartdashboard/SmartDashboard.h" -\#include "frc/livewindow/LiveWindow.h" +\#include "subsystems/#class($subsystem.name).h" +\#include "frc/SmartDashboard/SmartDashboard.h" +\#include +\#include "frc/LiveWindow/LiveWindow.h" #@autogenerated_code("includes", "") #parse("${exporter_path}Subsystem-includes.cpp") #end diff --git a/src/main/resources/export/cpp/PIDSubsystem.h b/src/main/resources/export/cpp/PIDSubsystem.h index 771cf942..4f95ab5d 100644 --- a/src/main/resources/export/cpp/PIDSubsystem.h +++ b/src/main/resources/export/cpp/PIDSubsystem.h @@ -3,7 +3,7 @@ #pragma once -\#include "frc/commands/PIDSubsystem.h" +\#include "frc2/Command/PIDSubsystem.h" #@autogenerated_code("includes", "") #parse("${exporter_path}Subsystem-includes.h") @@ -14,21 +14,21 @@ * * @author ExampleAuthor */ -class #class($subsystem.name): public frc::PIDSubsystem { - -#@autogenerated_code("declarations", " ") +class #class($subsystem.name): public frc2::PIDSubsystem { +private: +#@autogenerated_code("declarations", " ") #parse("${exporter_path}Subsystem-declarations.h") #end - public: - #class($subsystem.name)(); - double ReturnPIDInput() override; - void UsePIDOutput(double output) override; - void InitDefaultCommand() override; -#@autogenerated_code("constants", " ") +public: + #class($subsystem.name)(); + double ReturnPIDInput(); + void UsePIDOutput(double output); + void InitDefaultCommand(); +#@autogenerated_code("constants", " ") #parse("${exporter_path}Subsystem-constants.h") #end -#@autogenerated_code("cmdpidgetters"," ") +#@autogenerated_code("cmdpidgetters"," ") #parse("${exporter_path}Subsystem-pidgetters.h") #end }; diff --git a/src/main/resources/export/cpp/RobotContainer-constructors.cpp b/src/main/resources/export/cpp/RobotContainer-constructors.cpp new file mode 100644 index 00000000..c9c3ea85 --- /dev/null +++ b/src/main/resources/export/cpp/RobotContainer-constructors.cpp @@ -0,0 +1,40 @@ +#set($cmd = $robot.getProperty("Autonomous Command").getValue()) +#foreach( $component in $components ) +#if($component.getBase().getType() == "Command" && !($component.getProperty("Parameters").getValue().isEmpty()) && $component.name == $cmd) +m_setpoint, +#end +#if ($component.getBase().getType() == "Command" && $component.name == $cmd) + #if( $component.getProperty("Parameter presets").getValue().isEmpty() ) + #if ($component.getProperty("Requires").getValue() != "None") +&m_#required_subsystem($component))#if($component.getProperty("Add Timeout").value == true).withTimeout($component.getProperty("Timeout").value)#end{ + #else +){ + #end + #end +#end +#end + +##${Collections.reverse($components)} +#foreach( $component in $components ) +#if ($helper.exportsTo("OI", $component) + && ("#constructor($component)" != "" || "#extra($component)" != "") && "#type($component)" != "Joystick" && "#type($component)" != "JoystickButton") + #constructor($component) + #extra($component) +#end +#end + + +${Collections.reverse($components)} + // SmartDashboard Buttons +#foreach( $component in $components ) +#if ($component.getBase().getType() == "Command" + && $component.getProperty("Button on SmartDashboard").getValue()) +#if( $component.getProperty("Parameter presets").getValue().isEmpty()) + frc::SmartDashboard::PutData("$component.getName()", new #new_command_instantiation( $component, $component, $set.getParameters())); +#else +#foreach( $set in $component.getProperty("Parameter presets").getValue() ) + frc::SmartDashboard::PutData("$component.getName(): $set.getName()", new #new_command_instantiation( $component, $component, $set.getParameters() )); +#end +#end +#end +#end diff --git a/src/main/resources/export/cpp/RobotContainer-declarations.h b/src/main/resources/export/cpp/RobotContainer-declarations.h new file mode 100644 index 00000000..1c2a0e12 --- /dev/null +++ b/src/main/resources/export/cpp/RobotContainer-declarations.h @@ -0,0 +1,18 @@ +// The robot's subsystems +#foreach ($component in $components) +#if ("#type($component)" != "" +&& ("#type($component)" == "frc2::SubsystemBase" + || "#type($component)" == "PIDSubsystem")) + #class($component.getName()) m_#variable($component.getName()); +#end +#end + +// Joysticks +#foreach ($component in $components) +#if ($helper.exportsTo("OI", $component) + && "#type($component)" != "" + && "#type($component)" == "Joystick") + #constructor($component) + +#end +#end \ No newline at end of file diff --git a/src/main/resources/export/cpp/OI-functions.cpp b/src/main/resources/export/cpp/RobotContainer-functions.cpp similarity index 100% rename from src/main/resources/export/cpp/OI-functions.cpp rename to src/main/resources/export/cpp/RobotContainer-functions.cpp diff --git a/src/main/resources/export/cpp/RobotContainer-includes.h b/src/main/resources/export/cpp/RobotContainer-includes.h new file mode 100644 index 00000000..66fdadc1 --- /dev/null +++ b/src/main/resources/export/cpp/RobotContainer-includes.h @@ -0,0 +1,13 @@ +\#include +\#include +\#include + +#foreach( $component in $components ) +#if ($component.getBase().getType() == "Subsystem") +\#include "subsystems/#class(${component.name}).h" +#end +#end + + +${helper.getImports($robot, "RobotContainer")} +${helper.getImports($robot, "OI")} \ No newline at end of file diff --git a/src/main/resources/export/cpp/RobotContainer-prototypes.h b/src/main/resources/export/cpp/RobotContainer-prototypes.h new file mode 100644 index 00000000..5d9ac33a --- /dev/null +++ b/src/main/resources/export/cpp/RobotContainer-prototypes.h @@ -0,0 +1,8 @@ +${Collections.reverse($components)} +#foreach( $component in $components ) +#if ($helper.exportsTo("OI", $component) && "#prototype($component)" != ""){ + #prototype($component) +} + +#end +#end diff --git a/src/main/resources/export/cpp/RobotContainer-subsystem-default_command.cpp b/src/main/resources/export/cpp/RobotContainer-subsystem-default_command.cpp new file mode 100644 index 00000000..4239e54a --- /dev/null +++ b/src/main/resources/export/cpp/RobotContainer-subsystem-default_command.cpp @@ -0,0 +1,12 @@ +#foreach ($component in $components) +#if ("#type($component)" == "frc2::SubsystemBase" || "#type($component)" == "frc2::PIDSubsystem") +#foreach ($command in $commands) +#if($command.name == $component.getProperty("Default Command").value) +#set($params = $component.getProperty("Default command parameters").getValue()) +#if ($command != "None") + m_#required_subsystem($command).SetDefaultCommand(#new_command_instantiation($component, $command, $params)); +#end +#end +#end +#end +#end \ No newline at end of file diff --git a/src/main/resources/export/cpp/RobotContainer.cpp b/src/main/resources/export/cpp/RobotContainer.cpp new file mode 100644 index 00000000..e41ab1f2 --- /dev/null +++ b/src/main/resources/export/cpp/RobotContainer.cpp @@ -0,0 +1,44 @@ +#header() + +\#include "RobotContainer.h" +\#include +\#include + +#set($cmd = $robot.getProperty("Autonomous Command").getValue()) + +#foreach ($component in $components) +#if ($helper.exportsTo("OI", $component) + && "#type($component)" != "" + && "#type($component)" == "Joystick") + #set($joy = $component) +#end +#end + +RobotContainer::RobotContainer() : m_autonomousCommand( +#@autogenerated_code("constructor", " ") +#parse("${exporter_path}RobotContainer-constructors.cpp") +#end + + ConfigureButtonBindings(); + +#@autogenerated_code("default-commands", " ") +#parse("${exporter_path}RobotContainer-subsystem-default_command.cpp") +#end + +} + +void RobotContainer::ConfigureButtonBindings() { +#@autogenerated_code("buttons", " ") +#parse("${exporter_path}RobotContainer-buttons.cpp") +#end +} + +#@autogenerated_code("functions", "") +#parse("${exporter_path}RobotContainer-functions.cpp") +#end + + +frc2::Command* RobotContainer::GetAutonomousCommand() { + // An example command will be run in autonomous + return &m_autonomousCommand; +} \ No newline at end of file diff --git a/src/main/resources/export/cpp/RobotContainer.h b/src/main/resources/export/cpp/RobotContainer.h new file mode 100644 index 00000000..fa927a4d --- /dev/null +++ b/src/main/resources/export/cpp/RobotContainer.h @@ -0,0 +1,29 @@ +#set($command = $robot.getProperty("Autonomous Command").getValue()) +#header() + +#pragma once + +#@autogenerated_code("includes", "") +#parse("${exporter_path}RobotContainer-includes.h") +#end + +class RobotContainer { + +public: + RobotContainer(); + frc2::Command* GetAutonomousCommand(); + +#@autogenerated_code("prototypes", " ") +#parse("${exporter_path}RobotContainer-prototypes.h") +#end + +private: + +#@autogenerated_code("declarations", " ") +#parse("${exporter_path}RobotContainer-declarations.h") +#end + +#class($command) m_autonomousCommand; + +void ConfigureButtonBindings(); +}; \ No newline at end of file diff --git a/src/main/resources/export/cpp/SequentialCommandGroup.cpp b/src/main/resources/export/cpp/SequentialCommandGroup.cpp new file mode 100644 index 00000000..978a6373 --- /dev/null +++ b/src/main/resources/export/cpp/SequentialCommandGroup.cpp @@ -0,0 +1,16 @@ +#header() + +#@autogenerated_code("constructor", "") +#parse("${exporter_path}Command-constructor.cpp") +#end ##autogenerated + // Add your commands here, e.g. + // AddCommands(FooCommand(), BarCommand()); + + +} + +bool #class($command.name)::RunsWhenDisabled() const { +#@autogenerated_code("disabled", " ") +#parse("${exporter_path}Command-disabled.cpp") +#end +} \ No newline at end of file diff --git a/src/main/resources/export/cpp/SequentialCommandGroup.h b/src/main/resources/export/cpp/SequentialCommandGroup.h new file mode 100644 index 00000000..b9319ed2 --- /dev/null +++ b/src/main/resources/export/cpp/SequentialCommandGroup.h @@ -0,0 +1,32 @@ +#header() + +#set($command = $helper.getByName($command_name, $robot)) + +#pragma once + +#@autogenerated_code("includes", " ") +#parse("${exporter_path}command-includes.h") +#end +\#include + +/** + * + * + * @author ExampleAuthor + */ +class #class($command.name): public frc2:: CommandHelper{ +public: + +#@autogenerated_code("constructor", " ") +#parse("${exporter_path}Command-constructor-header.h") +#end + +bool RunsWhenDisabled() const override; + +private: +#@autogenerated_code("variables", " ") +#parse("${exporter_path}Command-constructor-variables.h") +#end +}; + diff --git a/src/main/resources/export/cpp/SetpointCommand-constructor-header.h b/src/main/resources/export/cpp/SetpointCommand-constructor-header.h index 6990512e..55737627 100644 --- a/src/main/resources/export/cpp/SetpointCommand-constructor-header.h +++ b/src/main/resources/export/cpp/SetpointCommand-constructor-header.h @@ -1,3 +1,5 @@ #set($command = $helper.getByName($command_name, $robot)) -#class($command.name)(double setpoint); +#class($command.name)(double setpoint, #class(${command.getProperty("Requires").getValue()})* m_#variable(${command.getProperty("Requires").getValue().toLowerCase()})); + + diff --git a/src/main/resources/export/cpp/SetpointCommand-constructor.cpp b/src/main/resources/export/cpp/SetpointCommand-constructor.cpp index f64a302e..06451335 100644 --- a/src/main/resources/export/cpp/SetpointCommand-constructor.cpp +++ b/src/main/resources/export/cpp/SetpointCommand-constructor.cpp @@ -1,4 +1,6 @@ #set($command = $helper.getByName($command_name, $robot)) -#class($command.name)::#class($command.name)(double setpoint) : Command() { - m_setpoint = setpoint; +#class($command.name)::#class($command.name)(double setpoint, #class(${command.getProperty("Requires").getValue()})* m_#variable(${command.getProperty("Requires").getValue().toLowerCase()})) : +m_setpoint(setpoint), m_#variable(${command.getProperty("Requires").getValue().toLowerCase()})(m_#variable(${command.getProperty("Requires").getValue().toLowerCase()})){ +SetName("#class($command.name)"); +AddRequirements({m_#variable(${command.getProperty("Requires").getValue().toLowerCase()})});} \ No newline at end of file diff --git a/src/main/resources/export/cpp/SetpointCommand-includes.h b/src/main/resources/export/cpp/SetpointCommand-includes.h new file mode 100644 index 00000000..0c2861b4 --- /dev/null +++ b/src/main/resources/export/cpp/SetpointCommand-includes.h @@ -0,0 +1,4 @@ + +\#include "frc2/command/CommandBase.h" +\#include "frc2/command/CommandHelper.h" +\#include "subsystems/#class(${command.getProperty("Requires").getValue()}).h" \ No newline at end of file diff --git a/src/main/resources/export/cpp/SetpointCommand-initialize.cpp b/src/main/resources/export/cpp/SetpointCommand-initialize.cpp index 8e4d4645..026e1b4b 100644 --- a/src/main/resources/export/cpp/SetpointCommand-initialize.cpp +++ b/src/main/resources/export/cpp/SetpointCommand-initialize.cpp @@ -1,3 +1,3 @@ #set($command = $helper.getByName($command_name, $robot)) - Robot::#variable(${command.getProperty("Requires").getValue()})->Enable(); - Robot::#variable(${command.getProperty("Requires").getValue()})->SetSetpoint(m_setpoint); + m_#variable(${command.getProperty("Requires").getValue().toLowerCase()})->Enable(); + m_#variable(${command.getProperty("Requires").getValue().toLowerCase()})->SetSetpoint(m_setpoint); diff --git a/src/main/resources/export/cpp/SetpointCommand-isFinished.cpp b/src/main/resources/export/cpp/SetpointCommand-isFinished.cpp index 49607eba..0884bb94 100644 --- a/src/main/resources/export/cpp/SetpointCommand-isFinished.cpp +++ b/src/main/resources/export/cpp/SetpointCommand-isFinished.cpp @@ -1,2 +1,2 @@ #set($command = $helper.getByName($command_name, $robot)) - return Robot::#variable(${command.getProperty("Requires").getValue()})->OnTarget(); + return m_#variable(${command.getProperty("Requires").getValue().toLowerCase()})->ReturnPIDInput() >= m_setpoint; diff --git a/src/main/resources/export/cpp/SetpointCommand.cpp b/src/main/resources/export/cpp/SetpointCommand.cpp index 9b3785b3..e1bd81f4 100644 --- a/src/main/resources/export/cpp/SetpointCommand.cpp +++ b/src/main/resources/export/cpp/SetpointCommand.cpp @@ -2,12 +2,14 @@ #set($command = $helper.getByName($command_name, $robot)) -\#include "Commands/#class($command.name).h" +\#include "commands/#class($command.name).h" #@autogenerated_code("constructor", "") -#parse("${exporter_path}Command-constructor.cpp") +#parse("${exporter_path}SetPointCommand-constructor.cpp") #end +} + // Called just before this Command runs the first time void #class($command.name)::Initialize() { #@autogenerated_code("initialize", " ") diff --git a/src/main/resources/export/cpp/SetpointCommand.h b/src/main/resources/export/cpp/SetpointCommand.h index 35099f81..b8879494 100644 --- a/src/main/resources/export/cpp/SetpointCommand.h +++ b/src/main/resources/export/cpp/SetpointCommand.h @@ -3,30 +3,31 @@ #pragma once -\#include "frc/commands/Command.h" -\#include "frc/commands/Subsystem.h" -\#include "Robot.h" +#@autogenerated_code("constructor", " ") +#parse("${exporter_path}SetpointCommand-includes.h") +#end /** * * * @author ExampleAuthor */ -class #class($command.name): public frc::Command { +class #class($command.name): public frc2::CommandHelper { public: #@autogenerated_code("constructor", " ") #parse("${exporter_path}SetpointCommand-constructor-header.h") #end - void Initialize() override; - void Execute() override; - bool IsFinished() override; - void End() override; - void Interrupted() override; + void Initialize() override; + void Execute() override; + bool IsFinished() override; + void End(); + void Interrupted(); private: #@autogenerated_code("variables", " ") double m_setpoint; + #class(${command.getProperty("Requires").getValue()})* m_#variable(${command.getProperty("Requires").getValue().toLowerCase()}); #end }; diff --git a/src/main/resources/export/cpp/Subsystem-constants.cpp b/src/main/resources/export/cpp/Subsystem-constants.cpp deleted file mode 100644 index 626c8bba..00000000 --- a/src/main/resources/export/cpp/Subsystem-constants.cpp +++ /dev/null @@ -1,5 +0,0 @@ -#set( $subsystem = $helper.getByName($subsystem_name, $robot) ) -#set( $constants = $subsystem.getProperty("Constants").getValue() ) -#foreach( $constant in $constants ) -#define_constant( $subsystem, $constant ) -#end \ No newline at end of file diff --git a/src/main/resources/export/cpp/Subsystem-constants.h b/src/main/resources/export/cpp/Subsystem-constants.h index 6ce93a7f..77fc1f44 100644 --- a/src/main/resources/export/cpp/Subsystem-constants.h +++ b/src/main/resources/export/cpp/Subsystem-constants.h @@ -1,5 +1,5 @@ #set( $subsystem = $helper.getByName($subsystem_name, $robot) ) #set( $constants = $subsystem.getProperty("Constants").getValue() ) #foreach( $constant in $constants ) - #declare_constant( $constant ) + #declare_constant( $constant ) #end \ No newline at end of file diff --git a/src/main/resources/export/cpp/Subsystem-declarations.cpp b/src/main/resources/export/cpp/Subsystem-declarations.cpp index 5de0fa9e..5dded5c5 100644 --- a/src/main/resources/export/cpp/Subsystem-declarations.cpp +++ b/src/main/resources/export/cpp/Subsystem-declarations.cpp @@ -1,8 +1,6 @@ #set($subsystem = $helper.getByName($subsystem_name, $robot)) #foreach ($component in $components) #if ($component.subsystem == $subsystem.subsystem && $component != $subsystem) - #constructor($component) - #livewindow($component) #extra($component) diff --git a/src/main/resources/export/cpp/Subsystem-declarations.h b/src/main/resources/export/cpp/Subsystem-declarations.h index 74522124..feb0bb73 100644 --- a/src/main/resources/export/cpp/Subsystem-declarations.h +++ b/src/main/resources/export/cpp/Subsystem-declarations.h @@ -1,7 +1,7 @@ #set($subsystem = $helper.getByName($subsystem_name, $robot)) #foreach ($component in $components) #if ($component.subsystem == $subsystem.subsystem && $component != $subsystem) - #declaration($component) + #declaration($component) #end #end diff --git a/src/main/resources/export/cpp/Subsystem-default_command.cpp b/src/main/resources/export/cpp/Subsystem-default_command.cpp deleted file mode 100644 index e102f777..00000000 --- a/src/main/resources/export/cpp/Subsystem-default_command.cpp +++ /dev/null @@ -1,9 +0,0 @@ -#set($subsystem = $helper.getByName($subsystem_name, $robot)) -#set($command = $subsystem.getProperty("Default Command").getValue()) -#set($params = $subsystem.getProperty("Default command parameters").getValue()) -#set($len = $params.size() - 2) -#set($last = $len + 1) - -#if ($command != "None") - SetDefaultCommand(#command_instantiation( $command $params )); -#end diff --git a/src/main/resources/export/cpp/Subsystem-includes.cpp b/src/main/resources/export/cpp/Subsystem-includes.cpp index ad046ddb..b8c3d37c 100644 --- a/src/main/resources/export/cpp/Subsystem-includes.cpp +++ b/src/main/resources/export/cpp/Subsystem-includes.cpp @@ -1,4 +1,2 @@ -#set($subsystem = $helper.getByName($subsystem_name, $robot)) -#set($default_command = $subsystem.getProperty("Default Command").getValue()) -#if($default_command != "None")\#include "Commands/#class($default_command).h" -#end +\#include "subsystems/#class($subsystem.name).h" +\#include diff --git a/src/main/resources/export/cpp/Subsystem-includes.h b/src/main/resources/export/cpp/Subsystem-includes.h index ff3dfe30..7ebbfb6e 100644 --- a/src/main/resources/export/cpp/Subsystem-includes.h +++ b/src/main/resources/export/cpp/Subsystem-includes.h @@ -1 +1,2 @@ +\#include ${helper.getImports($subsystem, "RobotMap")} \ No newline at end of file diff --git a/src/main/resources/export/cpp/Subsystem-pidgetters.cpp b/src/main/resources/export/cpp/Subsystem-pidgetters.cpp index 68417dd9..72423fb8 100644 --- a/src/main/resources/export/cpp/Subsystem-pidgetters.cpp +++ b/src/main/resources/export/cpp/Subsystem-pidgetters.cpp @@ -1,11 +1,11 @@ #foreach ($component in $components) #if ($component.getBase().getType() == "Command" && $subsystem_name == $component.getProperty("Requires").getValue() && $component.getProperty("Input").getValue()) -std::shared_ptr #class($subsystem_name)::Get#class($component.getProperty("Input").getValue())() { - return #variable($component.getProperty("Input").getValue()); +frc::PIDSource& #class($subsystem_name)::Get#class($component.getProperty("Input").getValue())() { + return m_#variable($component.getProperty("Input").getValue()); } -std::shared_ptr #class($subsystem_name)::Get#class($component.getProperty("Output").getValue())() { - return #variable($component.getProperty("Output").getValue()); +frc::PIDOutput& #class($subsystem_name)::Get#class($component.getProperty("Output").getValue())() { + return m_#variable($component.getProperty("Output").getValue()); } #end #end diff --git a/src/main/resources/export/cpp/Subsystem-pidgetters.h b/src/main/resources/export/cpp/Subsystem-pidgetters.h index a6b844f3..0944f3f1 100644 --- a/src/main/resources/export/cpp/Subsystem-pidgetters.h +++ b/src/main/resources/export/cpp/Subsystem-pidgetters.h @@ -1,7 +1,7 @@ #foreach ($component in $components) #if ($component.getBase().getType() == "Command" && $subsystem_name == $component.getProperty("Requires").getValue() && $component.getProperty("Input").getValue()) - std::shared_ptr Get#class($component.getProperty("Input").getValue())(); + frc::PIDSource& Get#class($component.getProperty("Input").getValue())(); - std::shared_ptr Get#class($component.getProperty("Output").getValue())(); + frc::PIDOutput& Get#class($component.getProperty("Output").getValue())(); #end #end diff --git a/src/main/resources/export/cpp/Subsystem.cpp b/src/main/resources/export/cpp/Subsystem.cpp index b8153b20..f4bb6215 100644 --- a/src/main/resources/export/cpp/Subsystem.cpp +++ b/src/main/resources/export/cpp/Subsystem.cpp @@ -2,29 +2,17 @@ #macro( klass $cmd )#if( "#type($cmd)" == "" )SendableSubsystemBase#elsefrc::#type($cmd)#end#end #header() -\#include "Subsystems/#class($subsystem.name).h" #@autogenerated_code("includes", "") #parse("${exporter_path}Subsystem-includes.cpp") #end -#@autogenerated_code("constants", "") -#parse("${exporter_path}Subsystem-constants.cpp") -#end - -#class($subsystem.name)::#class($subsystem.name)() : #klass($subsystem)("#class($subsystem.name)") { +#class($subsystem.name)::#class($subsystem.name)(){ +SetName("#class($subsystem.name)"); #@autogenerated_code("declarations", " ") #parse("${exporter_path}Subsystem-declarations.cpp") #end } -void #class($subsystem.name)::InitDefaultCommand() { - // Set the default command for a subsystem here. - // SetDefaultCommand(new MySpecialCommand()); -#@autogenerated_code("default_command", " ") -#parse("${exporter_path}Subsystem-default_command.cpp") -#end -} - void #class($subsystem.name)::Periodic() { // Put code here to be run every loop @@ -37,4 +25,3 @@ void #class($subsystem.name)::Periodic() { // Put methods for controlling this subsystem // here. Call these from Commands. - diff --git a/src/main/resources/export/cpp/Subsystem.h b/src/main/resources/export/cpp/Subsystem.h index 9c954385..c72f1b16 100644 --- a/src/main/resources/export/cpp/Subsystem.h +++ b/src/main/resources/export/cpp/Subsystem.h @@ -3,8 +3,6 @@ #header() #pragma once -\#include "frc/commands/Subsystem.h" - #@autogenerated_code("includes", "") #parse("${exporter_path}Subsystem-includes.h") #end @@ -14,21 +12,21 @@ * * @author ExampleAuthor */ -class #class($subsystem.name): public #klass($subsystem) { +class #class($subsystem.name): public frc2::SubsystemBase { private: - // It's desirable that everything possible is private except - // for methods that implement subsystem capabilities -#@autogenerated_code("declarations", " ") + // It's desirable that everything possible is private except + // for methods that implement subsystem capabilities +#@autogenerated_code("declarations", " ") #parse("${exporter_path}Subsystem-declarations.h") #end public: - #class($subsystem.name)(); - void InitDefaultCommand() override; - void Periodic() override; -#@autogenerated_code("cmdpidgetters", " ") + #class($subsystem.name)(); + + void Periodic() override; +#@autogenerated_code("cmdpidgetters", " ") #parse("${exporter_path}Subsystem-pidgetters.h") #end -#@autogenerated_code("constants", " ") +#@autogenerated_code("constants", " ") #parse("${exporter_path}Subsystem-constants.h") #end diff --git a/src/main/resources/export/cpp/TimedCommand-constructor.cpp b/src/main/resources/export/cpp/TimedCommand-constructor.cpp index 4fff00f2..10053a73 100644 --- a/src/main/resources/export/cpp/TimedCommand-constructor.cpp +++ b/src/main/resources/export/cpp/TimedCommand-constructor.cpp @@ -1,12 +1,9 @@ #set($command = $helper.getByName($command_name, $robot)) #class($command.name)::#class($command.name)(double timeout) : frc::TimedCommand(timeout) { - // Use Requires() here to declare subsystem dependencies - // eg. Requires(Robot::chassis.get()); -#@autogenerated_code("requires", " ") -#parse("${exporter_path}Command-requires.cpp") -#end -#if ( $command.getProperty("Run When Disabled").getValue() ) - SetRunWhenDisabled(true); -#end -} + // Use AddRequirements() here to declare subsystem dependencies + // eg. AddRequirements(Robot::chassis.get()); + SetName("#class($command.name)"); + #if (${command.getProperty("Requires").getValue()} != "None") + AddRequirements(m_#variable(${command.getProperty("Requires").getValue().toLowerCase()})); + #end diff --git a/src/main/resources/export/cpp/TimedCommand.cpp b/src/main/resources/export/cpp/TimedCommand.cpp index 7d4a07ba..10c48320 100644 --- a/src/main/resources/export/cpp/TimedCommand.cpp +++ b/src/main/resources/export/cpp/TimedCommand.cpp @@ -2,12 +2,14 @@ #set($command = $helper.getByName($command_name, $robot)) -\#include "Commands/#class($command.name).h" +\#include "commands/#class($command.name).h" #@autogenerated_code("constructor", "") #parse("${exporter_path}TimedCommand-constructor.cpp") #end +} + // Called just before this Command runs the first time void #class($command.name)::Initialize() { diff --git a/src/main/resources/export/cpp/TimedCommand.h b/src/main/resources/export/cpp/TimedCommand.h index 5cd2630d..e6c3d299 100644 --- a/src/main/resources/export/cpp/TimedCommand.h +++ b/src/main/resources/export/cpp/TimedCommand.h @@ -18,10 +18,10 @@ class #class($command.name): public frc::TimedCommand { #parse("${exporter_path}TimedCommand-constructor-header.h") #end - void Initialize() override; - void Execute() override; - void End() override; - void Interrupted() override; + void Initialize() override; + void Execute() override; + void End() override; + void Interrupted() override; private: #@autogenerated_code("variables", " ") diff --git a/src/main/resources/export/cpp/command-includes.h b/src/main/resources/export/cpp/command-includes.h new file mode 100644 index 00000000..c9ee1b3d --- /dev/null +++ b/src/main/resources/export/cpp/command-includes.h @@ -0,0 +1,7 @@ + +\#include +\#include + +#if (${command.getProperty("Requires").getValue()} != "None") +\#include "subsystems/#class(${command.getProperty("Requires").getValue()}).h" +#end \ No newline at end of file diff --git a/src/main/resources/export/cpp/files.yaml b/src/main/resources/export/cpp/files.yaml index 4e57563f..6b7738a4 100644 --- a/src/main/resources/export/cpp/files.yaml +++ b/src/main/resources/export/cpp/files.yaml @@ -1,7 +1,7 @@ ## Vendordep - !File - export: $project/vendordeps/WPILibOldCommands.json - source: ${exporters_path}vendordeps/WPILibOldCommands.json + export: $project/vendordeps/WPILibNewCommands.json + source: ${exporters_path}vendordeps/WPILibNewCommands.json update: None ## WPI Project Files @@ -76,34 +76,30 @@ - !File export: $project/src/main/cpp/Robot.cpp source: ${exporter_path}CommandBasedRobot.cpp - update: Modify - modifications: - autonomous: ${exporter_path}CommandBasedRobot-autonomous.cpp - constructors: ${exporter_path}CommandBasedRobot-constructors.cpp - initialization: ${exporter_path}CommandBasedRobot-initialization.cpp + update: None - !File export: $project/src/main/include/Robot.h source: ${exporter_path}CommandBasedRobot.h - update: Modify - modifications: - includes: ${exporter_path}CommandBasedRobot-includes.h - declarations: ${exporter_path}CommandBasedRobot-declarations.cpp + update: None - !File - export: $project/src/main/cpp/OI.cpp - source: ${exporter_path}OI.cpp + export: $project/src/main/cpp/RobotContainer.cpp + source: ${exporter_path}RobotContainer.cpp update: Modify modifications: - includes: ${exporter_path}OI-includes.h - constructors: ${exporter_path}OI-constructors.cpp - functions: ${exporter_path}OI-functions.cpp + constructor: ${exporter_path}RobotContainer-constructors.cpp + functions: ${exporter_path}RobotContainer-functions.cpp + buttons: ${exporter_path}RobotContainer-buttons.cpp + default-commands: ${exporter_path}RobotContainer-subsystem-default_command.cpp + - !File - export: $project/src/main/include/OI.h - source: ${exporter_path}OI.h + export: $project/src/main/include/RobotContainer.h + source: ${exporter_path}RobotContainer.h update: Modify modifications: - declarations: ${exporter_path}OI-declarations.h - prototypes: ${exporter_path}OI-prototypes.h + includes: ${exporter_path}RobotContainer-includes.h + declarations: ${exporter_path}RobotContainer-declarations.h + prototypes: ${exporter_path}RobotContainer-prototypes.h - !File export: $project/src/test/cpp/main.cpp @@ -113,22 +109,25 @@ ## Export Commands as files #if ($export_commands) #foreach ($command in $commands) -#if ($command.base.name == "Command Group") +#if ($command.base.name == "Sequential Command Group") - !File - export: $project/src/main/cpp/Commands/#class($command.name).cpp - source: ${exporter_path}CommandGroup.cpp + export: $project/src/main/cpp/commands/#class($command.name).cpp + source: ${exporter_path}SequentialCommandGroup.cpp update: None modifications: update: Modify - constructor: ${exporter_path}CommandGroup-constructor.cpp + constructor: ${exporter_path}Command-constructor.cpp + disabled: ${exporter_path}Command-disabled.cpp variables: command_name: ${command.name} - !File - export: $project/src/main/include/Commands/#class($command.name).h - source: ${exporter_path}CommandGroup.h + export: $project/src/main/include/commands/#class($command.name).h + source: ${exporter_path}SequentialCommandGroup.h update: Modify modifications: + includes: ${exporter_path}command-includes.h constructor: ${exporter_path}Command-constructor-header.h + variables: ${exporter_path}Command-constructor-variables.h variables: command_name: ${command.name} #elseif($command.base.name == "PID Command") @@ -138,35 +137,35 @@ update: Modify modifications: pid: ${exporter_path}PIDCommand-pid.cpp - requires: ${exporter_path}Command-requires.cpp source: ${exporter_path}PIDCommand-source.cpp output: ${exporter_path}PIDCommand-output.cpp constructor: ${exporter_path}PIDCommand-constructor.cpp variables: command_name: ${command.name} - !File - export: $project/src/main/include/Commands/#class($command.name).h + export: $project/src/main/include/commands/#class($command.name).h source: ${exporter_path}PIDCommand.h update: Modify modifications: constructor: ${exporter_path}Command-constructor-header.h + includes: ${exporter_path}PIDCommand-includes.h variables: ${exporter_path}Command-constructor-variables.h variables: command_name: ${command.name} #elseif($command.base.name == "Setpoint Command") - !File - export: $project/src/main/cpp/Commands/#class($command.name).cpp + export: $project/src/main/cpp/commands/#class($command.name).cpp source: ${exporter_path}SetpointCommand.cpp update: Modify modifications: - requires: ${exporter_path}Command-requires.cpp constructor: ${exporter_path}Command-constructor.cpp + includes: ${exporter_path}Setpointcommand-includes.cpp initialize: ${exporter_path}SetpointCommand-initialize.cpp isFinished: ${exporter_path}SetpointCommand-isFinished.cpp variables: command_name: ${command.name} - !File - export: $project/src/main/include/Commands/#class($command.name).h + export: $project/src/main/include/commands/#class($command.name).h source: ${exporter_path}SetpointCommand.h modifications: constructor: ${exporter_path}Command-constructor-header.h @@ -175,16 +174,15 @@ command_name: ${command.name} #elseif($command.base.name == "Timed Command") - !File - export: $project/src/main/cpp/Commands/#class($command.name).cpp + export: $project/src/main/cpp/commands/#class($command.name).cpp source: ${exporter_path}TimedCommand.cpp update: Modify modifications: - requires: ${exporter_path}Command-requires.cpp constructor: ${exporter_path}TimedCommand-constructor.cpp variables: command_name: ${command.name} - !File - export: $project/src/main/include/Commands/#class($command.name).h + export: $project/src/main/include/commands/#class($command.name).h source: ${exporter_path}TimedCommand.h modifications: constructor: ${exporter_path}TimedCommand-constructor-header.h @@ -193,16 +191,15 @@ command_name: ${command.name} #elseif($command.base.name == "Instant Command") - !File - export: $project/src/main/cpp/Commands/#class($command.name).cpp + export: $project/src/main/cpp/commands/#class($command.name).cpp source: ${exporter_path}InstantCommand.cpp update: Modify modifications: - requires: ${exporter_path}Command-requires.cpp constructor: ${exporter_path}InstantCommand-constructor.cpp variables: command_name: ${command.name} - !File - export: $project/src/main/include/Commands/#class($command.name).h + export: $project/src/main/include/commands/#class($command.name).h modifications: constructor: ${exporter_path}Command-constructor-header.h variables: ${exporter_path}Command-constructor-variables.h @@ -212,7 +209,7 @@ command_name: ${command.name} #elseif ($command.base.name == "Conditional Command") - !File - export: $project/src/main/cpp/Commands/#class($command.name).cpp + export: $project/src/main/cpp/commands/#class($command.name).cpp source: ${exporter_path}ConditionalCommand.cpp update: Modify modifications: @@ -220,27 +217,29 @@ variables: command_name: ${command.name} - !File - export: $project/src/main/include/Commands/#class($command.name).h + export: $project/src/main/include/commands/#class($command.name).h source: ${exporter_path}ConditionalCommand.h modifications: includes: ${exporter_path}ConditionalCommand-includes.h constructor: ${exporter_path}Command-constructor-header.h + variables: ${exporter_path}Command-constructor-variables.h update: Modify variables: command_name: ${command.name} #else - !File - export: $project/src/main/cpp/Commands/#class($command.name).cpp + export: $project/src/main/cpp/commands/#class($command.name).cpp source: ${exporter_path}Command.cpp update: Modify modifications: - requires: ${exporter_path}Command-requires.cpp constructor: ${exporter_path}Command-constructor.cpp + disabled: ${exporter_path}Command-disabled.cpp variables: command_name: ${command.name} - !File - export: $project/src/main/include/Commands/#class($command.name).h + export: $project/src/main/include/commands/#class($command.name).h modifications: + includes: ${exporter_path}command-includes.h constructor: ${exporter_path}Command-constructor-header.h variables: ${exporter_path}Command-constructor-variables.h source: ${exporter_path}Command.h @@ -256,7 +255,7 @@ #foreach ($subsystem in $subsystems) #if ($subsystem.base.name == "PID Subsystem") - !File - export: $project/src/main/cpp/Subsystems/#class($subsystem.name).cpp + export: $project/src/main/cpp/subsystems/#class($subsystem.name).cpp source: ${exporter_path}PIDSubsystem.cpp update: Modify modifications: @@ -265,13 +264,12 @@ pid: ${exporter_path}PIDSubsystem-pid.cpp source: ${exporter_path}PIDSubsystem-source.cpp output: ${exporter_path}PIDSubsystem-output.cpp - constants: ${exporter_path}Subsystem-constants.cpp cmdpidgetters: ${exporter_path}Subsystem-pidgetters.cpp includes: ${exporter_path}Subsystem-includes.cpp variables: subsystem_name: ${subsystem.name} - !File - export: $project/src/main/include/Subsystems/#class($subsystem.name).h + export: $project/src/main/include/subsystems/#class($subsystem.name).h source: ${exporter_path}PIDSubsystem.h update: Modify modifications: @@ -283,19 +281,17 @@ subsystem_name: ${subsystem.name} #else - !File - export: $project/src/main/cpp/Subsystems/#class($subsystem.name).cpp + export: $project/src/main/cpp/subsystems/#class($subsystem.name).cpp source: ${exporter_path}Subsystem.cpp update: Modify modifications: declarations: ${exporter_path}Subsystem-declarations.cpp - default_command: ${exporter_path}Subsystem-default_command.cpp - constants: ${exporter_path}Subsystem-constants.cpp cmdpidgetters: ${exporter_path}Subsystem-pidgetters.cpp includes: ${exporter_path}Subsystem-includes.cpp variables: subsystem_name: ${subsystem.name} - !File - export: $project/src/main/include/Subsystems/#class($subsystem.name).h + export: $project/src/main/include/subsystems/#class($subsystem.name).h source: ${exporter_path}Subsystem.h update: Modify modifications: diff --git a/src/main/resources/export/cpp/macros.vm b/src/main/resources/export/cpp/macros.vm index 6aec7fe9..9f65a8e0 100644 --- a/src/main/resources/export/cpp/macros.vm +++ b/src/main/resources/export/cpp/macros.vm @@ -17,13 +17,10 @@ #macro( constructor $component )${helper.getInstruction($component, "Construction")}#end ## Get the livewindow instruction of a robot component -#macro( livewindow $component )${helper.getInstruction($component, "LiveWindow")}#end +#macro( livewindow $component ) ${helper.getInstruction($component, "LiveWindow")}#end ## Get the extra instruction of a robot component -#macro( extra $component )${helper.getInstruction($component, "Extra")}#end - -## Get the prototype instruction of a robot component -#macro( prototype $component )${helper.getInstruction($component, "Prototype")}#end +#macro( extra $component ) ${helper.getInstruction($component, "Extra")}#end ## Get the function instruction of a robot component #macro( function $component )${helper.getInstruction($component, "Function")}#end @@ -33,14 +30,16 @@ ## Gets the C++ type of the parameter #macro( param_type $param ) -#if( $param.getType() == "String")std::string#elseif( $param.getType() == "boolean" )bool#elseif( $param.getType() == "byte" )uint8_t#else$param.getType()#end +#if( $param.getType() == "String")char*#elseif( $param.getType() == "boolean" )bool#elseif( $param.getType() == "byte" )uint8_t#else$param.getType()#end #end ## Generate command parameter declaration for C++ #macro( param_declaration_cpp $param )#param_type( $param ) $param.getName()#end ## Generate parameter use -#macro( param_set $param )#if( $param.isSubsystemConstant() )#cppify( $param )#elseif( $param.isReference() )$param.getValue().replaceAll("^\\$", "")#elseif( $param.getType() == "String" )"$param.getValue()"#else$param.getValue()#end#end +#macro( param_set $param )#if( $param.isSubsystemConstant() )#constant_use( $param )#elseif( $param.isReference() )$param.getValue().substring(1)#else#if( $param.getType() == "String" )"$param.getValue()"#else#if( $param.getType() == "byte" )(byte) #end$param.getValue()#if( $param.getType() == "long" )L#end#end#end#end + +#macro( constant_use $constant )#class( $helper.stringSplit($constant.getValue(), "\.").get(0) ).$helper.stringSplit($constant.getValue(), "\.").get(1)#end ## Generates 'new MyCommand(arg0, arg1, arg2, ...)' #macro( command_instantiation $command $params ) @@ -48,26 +47,41 @@ #set($last = $len + 1) new #class($command)(#if( $len >= 0 )#foreach($i in [0..$len])#param_set( $params.get($i) ), #end#end#if( $last >= 0 )#param_set( $params.get($last) )#end)#end -## Generate constant declaration (for .h files) -#macro( declare_constant $constant ) -const static #param_type( $constant ) $constant.getName(); -#end +## Generates 'new MyCommand(arg0, arg1, arg2, ...)' +#macro( new_command_instantiation $component $command $params ) +#set($len = $params.size() - 1) +#class($command.name)(#if($command.getProperty("Requires").getValue() != "None")#if($len >= 0)#command_params($params), &m_#required_subsystem($command)#else &m_#required_subsystem($command) #end#else#if($len >= 0)#command_params($params)#end#end)#end -## Generate constant defenition (for .cpp files) -#macro( define_constant $subsystem $constant ) -const #param_type( $constant ) #class( $subsystem.name )::$constant.getName() = #if( $constant.getType() == "String" )"$constant.getValue()"#else$constant.getValue()#end; -#end -## Converts subsystem.constant to subsystem::constant -#macro( cppify $constant )#get_subsystem( $constant )::#get_name( $constant )#end +## Generates 'new command_params(arg0, arg1, arg2, ...)' +#macro( command_params $params ) +#set($len = $params.size() - 2) +#set($last = $len + 1) +#if( $len >= 0 )#foreach($i in [0..$len])#param_set( $params.get($i) ), #end#end#if( $last >= 0 )#param_set( $params.get($last) )#end#end + +## Generate required_subsystem +#macro( required_subsystem $command ) +#variable(${command.getProperty("Requires").getValue()}) +#end -#macro( get_subsystem $constant )#class( $helper.stringSplit($constant.getValue(), "\.").get(0) )#end -#macro( get_name $constant )$helper.stringSplit($constant.getValue(), "\.").get(1)#end +## Get the prototype instruction of a robot component +#macro( prototype $component )${helper.getInstruction($component, "Prototype")}#end ## Generate autogenerated code blocks #macro( autogenerated_code $id $space ) $space// BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=$id.toUpperCase() -$bodyContent$space// END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=$id.toUpperCase() +$bodyContent +$space// END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=$id.toUpperCase() +#end + +## Gets the C++ type of the parameter +#macro( param_type $param ) +#if( $param.getType() == "String")char*#elseif( $param.getType() == "boolean" )bool#elseif( $param.getType() == "byte" )uint8_t#else$param.getType()#end +#end + +## Generate constant declaration (for .h files) +#macro( declare_constant $constant ) +static constexpr const #param_type( $constant ) $constant.getName() = #if( $constant.getType() == "String" )"$constant.getValue()"#else$constant.getValue()#end; #end ## Generate the header @@ -82,4 +96,4 @@ $bodyContent$space// END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=$id.toUpperC // update. Deleting the comments indicating the section will prevent // it from being updated in the future. -#end \ No newline at end of file +#end diff --git a/src/test/java/robotbuilder/TestUtils.java b/src/test/java/robotbuilder/TestUtils.java index 98879df1..2aba7cb1 100644 --- a/src/test/java/robotbuilder/TestUtils.java +++ b/src/test/java/robotbuilder/TestUtils.java @@ -93,7 +93,6 @@ public static RobotTree generateTestTree() { wrist.getProperty("P").setValueAndUpdate(2); wrist.getProperty("I").setValueAndUpdate(1); wrist.getProperty("D").setValueAndUpdate(-1); - wrist.getProperty("Limit Input").setValueAndUpdate(true); wrist.getProperty("Continuous").setValueAndUpdate(true); RobotComponent wristMotor = new RobotComponent("Motor", "Speed Controller", tree); wristMotor.setProperty("Type", "Jaguar");