Fix incomplete .styleguide (#2113)

Also clean up other .styleguides.

Fixes #2111.
This commit is contained in:
Tyler Veness
2019-11-20 22:44:18 -08:00
committed by Peter Johnson
parent ffa4b907c0
commit 9a8067465c
20 changed files with 141 additions and 104 deletions

View File

@@ -130,8 +130,9 @@ class Command : public frc::ErrorBase {
* @param requirements the required subsystems
* @return the decorated command
*/
SequentialCommandGroup BeforeStarting(std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements = {}) &&;
SequentialCommandGroup BeforeStarting(
std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements = {}) &&;
/**
* Decorates this command with a runnable to run after the command finishes.
@@ -140,8 +141,9 @@ class Command : public frc::ErrorBase {
* @param requirements the required subsystems
* @return the decorated command
*/
SequentialCommandGroup AndThen(std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements = {}) &&;
SequentialCommandGroup AndThen(
std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements = {}) &&;
/**
* Decorates this command to run perpetually, ignoring its ordinary end

View File

@@ -9,6 +9,7 @@
#include <functional>
#include <initializer_list>
#include <utility>
#include <frc/controller/ProfiledPIDController.h>
#include <units/units.h>
@@ -50,10 +51,10 @@ class ProfiledPIDCommand
std::function<State()> goalSource,
std::function<void(double, State)> useOutput,
std::initializer_list<Subsystem*> requirements = {})
: m_controller{controller},
m_measurement{std::move(measurementSource)},
m_goal{std::move(goalSource)},
m_useOutput{std::move(useOutput)} {
: m_controller{controller},
m_measurement{std::move(measurementSource)},
m_goal{std::move(goalSource)},
m_useOutput{std::move(useOutput)} {
AddRequirements(requirements);
}
@@ -72,11 +73,11 @@ class ProfiledPIDCommand
std::function<units::unit_t<Distance>> goalSource,
std::function<void(double, State)> useOutput,
std::initializer_list<Subsystem*> requirements)
: ProfiledPIDCommand(controller, measurementSource,
[&goalSource]() {
return State{goalSource(), 0_mps};
},
useOutput, requirements) {}
: ProfiledPIDCommand(controller, measurementSource,
[&goalSource]() {
return State{goalSource(), 0_mps};
},
useOutput, requirements) {}
/**
* Creates a new PIDCommand, which controls the given output with a
@@ -92,8 +93,8 @@ class ProfiledPIDCommand
std::function<units::unit_t<Distance>> measurementSource,
State goal, std::function<void(double, State)> useOutput,
std::initializer_list<Subsystem*> requirements)
: ProfiledPIDCommand(controller, measurementSource, [goal] { return goal; },
useOutput, requirements) {}
: ProfiledPIDCommand(controller, measurementSource,
[goal] { return goal; }, useOutput, requirements) {}
/**
* Creates a new PIDCommand, which controls the given output with a
@@ -110,8 +111,8 @@ class ProfiledPIDCommand
units::meter_t goal,
std::function<void(double, State)> useOutput,
std::initializer_list<Subsystem*> requirements)
: ProfiledPIDCommand(controller, measurementSource, [goal] { return goal; },
useOutput, requirements) {}
: ProfiledPIDCommand(controller, measurementSource,
[goal] { return goal; }, useOutput, requirements) {}
ProfiledPIDCommand(ProfiledPIDCommand&& other) = default;
@@ -133,9 +134,7 @@ class ProfiledPIDCommand
*
* @return The ProfiledPIDController
*/
frc::ProfiledPIDController<Distance>& GetController() {
return m_controller;
}
frc::ProfiledPIDController<Distance>& GetController() { return m_controller; }
protected:
frc::ProfiledPIDController<Distance> m_controller;

View File

@@ -34,7 +34,7 @@ class ProfiledPIDSubsystem : public SubsystemBase {
* @param controller the ProfiledPIDController to use
*/
explicit ProfiledPIDSubsystem(frc::ProfiledPIDController<Distance> controller)
: m_controller{controller} {}
: m_controller{controller} {}
void Periodic() override {
if (m_enabled) {
@@ -79,18 +79,16 @@ class ProfiledPIDSubsystem : public SubsystemBase {
* Disables the PID control. Sets output to zero.
*/
virtual void Disable() {
UseOutput(0, State{Distance_t(0), Velocity_t(0)});
m_enabled = false;
}
UseOutput(0, State{Distance_t(0), Velocity_t(0)});
m_enabled = false;
}
/**
* Returns the ProfiledPIDController.
*
* @return The controller.
*/
frc::ProfiledPIDController<Distance>& GetController() {
return m_controller;
}
frc::ProfiledPIDController<Distance>& GetController() { return m_controller; }
protected:
frc::ProfiledPIDController<Distance> m_controller;

View File

@@ -17,9 +17,9 @@
#include <frc/geometry/Pose2d.h>
#include <frc/kinematics/DifferentialDriveKinematics.h>
#include <frc/trajectory/Trajectory.h>
#include <frc2/Timer.h>
#include <units/units.h>
#include "frc2/Timer.h"
#include "frc2/command/CommandBase.h"
#include "frc2/command/CommandHelper.h"
@@ -42,7 +42,6 @@ namespace frc2 {
* @see Trajectory
*/
class RamseteCommand : public CommandHelper<CommandBase, RamseteCommand> {
public:
/**
* Constructs a new RamseteCommand that, when executed, will follow the
@@ -58,7 +57,8 @@ class RamseteCommand : public CommandHelper<CommandBase, RamseteCommand> {
* the odometry classes to provide this.
* @param controller The RAMSETE controller used to follow the
* trajectory.
* @param feedforward A component for calculating the feedforward for the drive.
* @param feedforward A component for calculating the feedforward for the
* drive.
* @param kinematics The kinematics for the robot drivetrain.
* @param wheelSpeeds A function that supplies the speeds of the left
* and right sides of the robot drive.

View File

@@ -13,9 +13,9 @@
#endif
#include <memory>
#include <type_traits>
#include <unordered_map>
#include <utility>
#include <type_traits>
#include <vector>
#include "frc2/command/CommandBase.h"

View File

@@ -11,8 +11,8 @@
#include <initializer_list>
#include <frc/trajectory/TrapezoidProfile.h>
#include <frc2/Timer.h>
#include "frc2/Timer.h"
#include "frc2/command/CommandBase.h"
#include "frc2/command/CommandHelper.h"
@@ -31,6 +31,7 @@ class TrapezoidProfileCommand
units::compound_unit<Distance, units::inverse<units::seconds>>;
using Velocity_t = units::unit_t<Velocity>;
using State = typename frc::TrapezoidProfile<Distance>::State;
public:
/**
* Creates a new TrapezoidProfileCommand that will execute the given
@@ -39,10 +40,9 @@ class TrapezoidProfileCommand
* @param profile The motion profile to execute.
* @param output The consumer for the profile output.
*/
TrapezoidProfileCommand(
frc::TrapezoidProfile<Distance> profile,
std::function<void(State)> output,
std::initializer_list<Subsystem*> requirements)
TrapezoidProfileCommand(frc::TrapezoidProfile<Distance> profile,
std::function<void(State)> output,
std::initializer_list<Subsystem*> requirements)
: m_profile(profile), m_output(output) {
AddRequirements(requirements);
}
@@ -52,9 +52,7 @@ class TrapezoidProfileCommand
m_timer.Start();
}
void Execute() override {
m_output(m_profile.Calculate(m_timer.Get()));
}
void Execute() override { m_output(m_profile.Calculate(m_timer.Get())); }
void End(bool interrupted) override { m_timer.Stop(); }

View File

@@ -7,15 +7,16 @@
#pragma once
#include "frc2/command/SubsystemBase.h"
#include "frc/trajectory/TrapezoidProfile.h"
#include <frc/trajectory/TrapezoidProfile.h>
#include <units/units.h>
#include "frc2/command/SubsystemBase.h"
namespace frc2 {
/**
* A subsystem that generates and runs trapezoidal motion profiles automatically. The user
* specifies how to use the current state of the motion profile by overriding the `UseState` method.
* A subsystem that generates and runs trapezoidal motion profiles
* automatically. The user specifies how to use the current state of the motion
* profile by overriding the `UseState` method.
*/
template <class Distance>
class TrapezoidProfileSubsystem : public SubsystemBase {
@@ -25,39 +26,42 @@ class TrapezoidProfileSubsystem : public SubsystemBase {
using Velocity_t = units::unit_t<Velocity>;
using State = typename frc::TrapezoidProfile<Distance>::State;
using Constraints = typename frc::TrapezoidProfile<Distance>::Constraints;
public:
/**
* Creates a new TrapezoidProfileSubsystem.
*
* @param constraints The constraints (maximum velocity and acceleration) for the profiles.
* @param initialPosition The initial position of the controller mechanism when the subsystem
* is constructed.
* @param constraints The constraints (maximum velocity and acceleration)
* for the profiles.
* @param initialPosition The initial position of the controller mechanism
* when the subsystem is constructed.
* @param period The period of the main robot loop, in seconds.
*/
TrapezoidProfileSubsystem(Constraints constraints,
Distance_t position,
TrapezoidProfileSubsystem(Constraints constraints, Distance_t position,
units::second_t period = 20_ms)
: m_constraints(constraints),
m_state{position, Velocity_t(0)},
m_period(period) {}
: m_constraints(constraints),
m_state{position, Velocity_t(0)},
m_period(period) {}
void Periodic() override {
auto profile = frc::TrapezoidProfile<Distance>(m_constraints, GetGoal(), m_state);
auto profile =
frc::TrapezoidProfile<Distance>(m_constraints, GetGoal(), m_state);
m_state = profile.Calculate(m_period);
UseState(m_state);
}
/**
* Users should override this to return the goal state for the subsystem's motion profile.
* Users should override this to return the goal state for the subsystem's
* motion profile.
*
* @return The goal state for the subsystem's motion profile.
*/
virtual State GetGoal() = 0;
protected:
/**
* Users should override this to consume the current state of the motion profile.
* Users should override this to consume the current state of the motion
* profile.
*
* @param state The current state of the motion profile.
*/
@@ -68,4 +72,4 @@ class TrapezoidProfileSubsystem : public SubsystemBase {
State m_state;
units::second_t m_period;
};
}
} // namespace frc2

View File

@@ -7,9 +7,9 @@
#pragma once
#include <frc2/Timer.h>
#include <units/units.h>
#include "frc2/Timer.h"
#include "frc2/command/CommandBase.h"
#include "frc2/command/CommandHelper.h"

View File

@@ -7,13 +7,13 @@
#pragma once
#include <frc2/command/Command.h>
#include <frc2/command/CommandScheduler.h>
#include <atomic>
#include <memory>
#include <utility>
#include "frc2/command/Command.h"
#include "frc2/command/CommandScheduler.h"
namespace frc2 {
class Command;
/**
@@ -149,8 +149,9 @@ class Trigger {
* @param toRun the runnable to execute.
* @param requirements the required subsystems.
*/
Trigger WhileActiveContinous(std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements = {});
Trigger WhileActiveContinous(
std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements = {});
/**
* Binds a command to be started when the trigger becomes active, and