From 5ca00dddbeffd825f41efa17259574e2d75f4d08 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Sat, 27 Jan 2018 01:01:15 -0800 Subject: [PATCH] Added TimedRobot::GetPeriod() (#915) Fixes #914. --- wpilibc/src/main/native/cpp/TimedRobot.cpp | 7 ++++++- wpilibc/src/main/native/include/TimedRobot.h | 4 +++- .../src/main/java/edu/wpi/first/wpilibj/TimedRobot.java | 9 ++++++++- 3 files changed, 17 insertions(+), 3 deletions(-) diff --git a/wpilibc/src/main/native/cpp/TimedRobot.cpp b/wpilibc/src/main/native/cpp/TimedRobot.cpp index 9ef480e112..eef3f5c993 100644 --- a/wpilibc/src/main/native/cpp/TimedRobot.cpp +++ b/wpilibc/src/main/native/cpp/TimedRobot.cpp @@ -43,10 +43,15 @@ void TimedRobot::SetPeriod(double period) { m_period = period; if (m_startLoop) { - m_loop->StartPeriodic(m_period); + m_loop->StartPeriodic(period); } } +/** + * Get time period between calls to Periodic() functions. + */ +double TimedRobot::GetPeriod() const { return m_period; } + TimedRobot::TimedRobot() { m_loop = std::make_unique(&TimedRobot::LoopFunc, this); diff --git a/wpilibc/src/main/native/include/TimedRobot.h b/wpilibc/src/main/native/include/TimedRobot.h index ca348dbad5..ba2f812a5d 100644 --- a/wpilibc/src/main/native/include/TimedRobot.h +++ b/wpilibc/src/main/native/include/TimedRobot.h @@ -7,6 +7,7 @@ #pragma once +#include #include #include "IterativeRobotBase.h" @@ -30,13 +31,14 @@ class TimedRobot : public IterativeRobotBase { void StartCompetition() override; void SetPeriod(double seconds); + double GetPeriod() const; protected: TimedRobot(); virtual ~TimedRobot(); private: - double m_period = kDefaultPeriod; + std::atomic m_period{kDefaultPeriod}; // Prevents loop from starting if user calls SetPeriod() in RobotInit() bool m_startLoop = false; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java index d533313dc1..06aa6165f6 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java @@ -21,7 +21,7 @@ import edu.wpi.first.wpilibj.hal.HAL; public class TimedRobot extends IterativeRobotBase { public static final double DEFAULT_PERIOD = 0.02; - private double m_period = DEFAULT_PERIOD; + private volatile double m_period = DEFAULT_PERIOD; // Prevents loop from starting if user calls setPeriod() in robotInit() private boolean m_startLoop = false; @@ -68,4 +68,11 @@ public class TimedRobot extends IterativeRobotBase { m_loop.startPeriodic(m_period); } } + + /** + * Get time period between calls to Periodic() functions. + */ + public double getPeriod() { + return m_period; + } }