mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
Add simulation GUI plugin
This uses Dear Imgui to provide a cross-platform integrated GUI for robot simulation. The GUI provides fully integrated DS and joystick support so it's not necessary to run the official DS.
This commit is contained in:
@@ -29,6 +29,7 @@ includeOtherLibs {
|
||||
^cameraserver/
|
||||
^cscore
|
||||
^hal/
|
||||
^imgui
|
||||
^mockdata/
|
||||
^networktables/
|
||||
^ntcore
|
||||
|
||||
@@ -5,5 +5,5 @@ repositories {
|
||||
}
|
||||
}
|
||||
dependencies {
|
||||
compile "edu.wpi.first:native-utils:2020.0.7"
|
||||
compile "edu.wpi.first:native-utils:2020.1.2"
|
||||
}
|
||||
|
||||
@@ -30,6 +30,7 @@ include 'simulation:frc_gazebo_plugins'
|
||||
include 'simulation:halsim_gazebo'
|
||||
include 'simulation:lowfi_simulation'
|
||||
include 'simulation:halsim_ds_socket'
|
||||
include 'simulation:halsim_gui'
|
||||
include 'cameraserver'
|
||||
include 'cameraserver:multiCameraServer'
|
||||
include 'myRobot'
|
||||
|
||||
@@ -1,6 +1,7 @@
|
||||
import org.gradle.internal.os.OperatingSystem
|
||||
|
||||
nativeUtils.addWpiNativeUtils()
|
||||
nativeUtils.withRoboRIO()
|
||||
nativeUtils.withRaspbian()
|
||||
nativeUtils.withBionic()
|
||||
nativeUtils {
|
||||
@@ -10,6 +11,7 @@ nativeUtils {
|
||||
niLibVersion = "2020.2.2"
|
||||
opencvVersion = "3.4.7-1"
|
||||
googleTestVersion = "1.9.0-3-437e100"
|
||||
imguiVersion = "1.72b-1"
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1,3 +1,4 @@
|
||||
add_subdirectory(halsim_gui)
|
||||
add_subdirectory(halsim_print)
|
||||
add_subdirectory(halsim_lowfi)
|
||||
add_subdirectory(halsim_ds_nt)
|
||||
|
||||
16
simulation/halsim_gui/CMakeLists.txt
Normal file
16
simulation/halsim_gui/CMakeLists.txt
Normal file
@@ -0,0 +1,16 @@
|
||||
project(halsim_gui)
|
||||
|
||||
include(CompileWarnings)
|
||||
|
||||
file(GLOB halsim_gui_src src/main/native/cpp/*.cpp)
|
||||
|
||||
add_library(halsim_gui MODULE ${halsim_gui_src})
|
||||
wpilib_target_warnings(halsim_gui)
|
||||
set_target_properties(halsim_gui PROPERTIES DEBUG_POSTFIX "d")
|
||||
target_link_libraries(halsim_gui PUBLIC hal PRIVATE imgui)
|
||||
|
||||
target_include_directories(halsim_gui PRIVATE src/main/native/include)
|
||||
|
||||
set_property(TARGET halsim_gui PROPERTY FOLDER "libraries")
|
||||
|
||||
install(TARGETS halsim_gui EXPORT halsim_gui DESTINATION "${main_lib_dest}")
|
||||
36
simulation/halsim_gui/build.gradle
Normal file
36
simulation/halsim_gui/build.gradle
Normal file
@@ -0,0 +1,36 @@
|
||||
if (!project.hasProperty('onlylinuxathena') && !project.hasProperty('onlylinuxraspbian') && !project.hasProperty('onlylinuxaarch64bionic')) {
|
||||
|
||||
description = "A plugin that creates a simulation gui"
|
||||
|
||||
ext {
|
||||
includeWpiutil = true
|
||||
pluginName = 'halsim_gui'
|
||||
}
|
||||
|
||||
apply plugin: 'google-test-test-suite'
|
||||
|
||||
|
||||
ext {
|
||||
staticGtestConfigs = [:]
|
||||
}
|
||||
|
||||
staticGtestConfigs["${pluginName}Test"] = []
|
||||
apply from: "${rootDir}/shared/googletest.gradle"
|
||||
|
||||
apply from: "${rootDir}/shared/plugins/setupBuild.gradle"
|
||||
|
||||
model {
|
||||
binaries {
|
||||
all {
|
||||
nativeUtils.useRequiredLibrary(it, 'imgui_static')
|
||||
if (it.targetPlatform.operatingSystem.isWindows()) {
|
||||
it.linker.args << 'Gdi32.lib' << 'Shell32.lib'
|
||||
} else if (it.targetPlatform.operatingSystem.isMacOsX()) {
|
||||
it.linker.args << '-framework' << 'Cocoa' << '-framework' << 'IOKit' << '-framework' << 'CoreFoundation' << '-framework' << 'CoreVideo'
|
||||
} else {
|
||||
it.linker.args << '-lX11' << '-lvulkan'
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
8
simulation/halsim_gui/src/dev/native/cpp/main.cpp
Normal file
8
simulation/halsim_gui/src/dev/native/cpp/main.cpp
Normal file
@@ -0,0 +1,8 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
int main() {}
|
||||
@@ -0,0 +1,51 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "AccelerometerGui.h"
|
||||
|
||||
#include <cstdio>
|
||||
|
||||
#include <hal/Value.h>
|
||||
#include <imgui.h>
|
||||
#include <mockdata/AccelerometerData.h>
|
||||
|
||||
#include "SimDeviceGui.h"
|
||||
|
||||
using namespace halsimgui;
|
||||
|
||||
static void DisplayAccelerometers() {
|
||||
if (!HALSIM_GetAccelerometerActive(0)) return;
|
||||
if (SimDeviceGui::StartDevice("BuiltInAccel")) {
|
||||
HAL_Value value;
|
||||
|
||||
// Range
|
||||
value = HAL_MakeEnum(HALSIM_GetAccelerometerRange(0));
|
||||
static const char* rangeOptions[] = {"2G", "4G", "8G"};
|
||||
SimDeviceGui::DisplayValue("Range", true, &value, rangeOptions, 3);
|
||||
|
||||
// X Accel
|
||||
value = HAL_MakeDouble(HALSIM_GetAccelerometerX(0));
|
||||
if (SimDeviceGui::DisplayValue("X Accel", false, &value))
|
||||
HALSIM_SetAccelerometerX(0, value.data.v_double);
|
||||
|
||||
// Y Accel
|
||||
value = HAL_MakeDouble(HALSIM_GetAccelerometerY(0));
|
||||
if (SimDeviceGui::DisplayValue("Y Accel", false, &value))
|
||||
HALSIM_SetAccelerometerY(0, value.data.v_double);
|
||||
|
||||
// Z Accel
|
||||
value = HAL_MakeDouble(HALSIM_GetAccelerometerZ(0));
|
||||
if (SimDeviceGui::DisplayValue("Z Accel", false, &value))
|
||||
HALSIM_SetAccelerometerZ(0, value.data.v_double);
|
||||
|
||||
SimDeviceGui::FinishDevice();
|
||||
}
|
||||
}
|
||||
|
||||
void AccelerometerGui::Initialize() {
|
||||
SimDeviceGui::Add(DisplayAccelerometers);
|
||||
}
|
||||
17
simulation/halsim_gui/src/main/native/cpp/AccelerometerGui.h
Normal file
17
simulation/halsim_gui/src/main/native/cpp/AccelerometerGui.h
Normal file
@@ -0,0 +1,17 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
namespace halsimgui {
|
||||
|
||||
class AccelerometerGui {
|
||||
public:
|
||||
static void Initialize();
|
||||
};
|
||||
|
||||
} // namespace halsimgui
|
||||
45
simulation/halsim_gui/src/main/native/cpp/AnalogGyroGui.cpp
Normal file
45
simulation/halsim_gui/src/main/native/cpp/AnalogGyroGui.cpp
Normal file
@@ -0,0 +1,45 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "AnalogGyroGui.h"
|
||||
|
||||
#include <cstdio>
|
||||
|
||||
#include <hal/Ports.h>
|
||||
#include <hal/Value.h>
|
||||
#include <imgui.h>
|
||||
#include <mockdata/AnalogGyroData.h>
|
||||
|
||||
#include "SimDeviceGui.h"
|
||||
|
||||
using namespace halsimgui;
|
||||
|
||||
static void DisplayAnalogGyros() {
|
||||
static int numAccum = HAL_GetNumAccumulators();
|
||||
for (int i = 0; i < numAccum; ++i) {
|
||||
if (!HALSIM_GetAnalogGyroInitialized(i)) continue;
|
||||
char name[32];
|
||||
std::snprintf(name, sizeof(name), "AnalogGyro[%d]", i);
|
||||
if (SimDeviceGui::StartDevice(name)) {
|
||||
HAL_Value value;
|
||||
|
||||
// angle
|
||||
value = HAL_MakeDouble(HALSIM_GetAnalogGyroAngle(i));
|
||||
if (SimDeviceGui::DisplayValue("Angle", false, &value))
|
||||
HALSIM_SetAnalogGyroAngle(i, value.data.v_double);
|
||||
|
||||
// rate
|
||||
value = HAL_MakeDouble(HALSIM_GetAnalogGyroRate(i));
|
||||
if (SimDeviceGui::DisplayValue("Rate", false, &value))
|
||||
HALSIM_SetAnalogGyroRate(i, value.data.v_double);
|
||||
|
||||
SimDeviceGui::FinishDevice();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void AnalogGyroGui::Initialize() { SimDeviceGui::Add(DisplayAnalogGyros); }
|
||||
17
simulation/halsim_gui/src/main/native/cpp/AnalogGyroGui.h
Normal file
17
simulation/halsim_gui/src/main/native/cpp/AnalogGyroGui.h
Normal file
@@ -0,0 +1,17 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
namespace halsimgui {
|
||||
|
||||
class AnalogGyroGui {
|
||||
public:
|
||||
static void Initialize();
|
||||
};
|
||||
|
||||
} // namespace halsimgui
|
||||
54
simulation/halsim_gui/src/main/native/cpp/AnalogInputGui.cpp
Normal file
54
simulation/halsim_gui/src/main/native/cpp/AnalogInputGui.cpp
Normal file
@@ -0,0 +1,54 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "AnalogInputGui.h"
|
||||
|
||||
#include <cstdio>
|
||||
|
||||
#include <hal/Ports.h>
|
||||
#include <imgui.h>
|
||||
#include <mockdata/AnalogGyroData.h>
|
||||
#include <mockdata/AnalogInData.h>
|
||||
#include <mockdata/SimDeviceData.h>
|
||||
|
||||
#include "HALSimGui.h"
|
||||
|
||||
using namespace halsimgui;
|
||||
|
||||
static void DisplayAnalogInputs() {
|
||||
ImGui::Text("(Use Ctrl+Click to edit value)");
|
||||
bool hasInputs = false;
|
||||
static int numAnalog = HAL_GetNumAnalogInputs();
|
||||
static int numAccum = HAL_GetNumAccumulators();
|
||||
for (int i = 0; i < numAnalog; ++i) {
|
||||
if (HALSIM_GetAnalogInInitialized(i)) {
|
||||
hasInputs = true;
|
||||
char name[32];
|
||||
std::snprintf(name, sizeof(name), "In[%d]", i);
|
||||
if (i < numAccum && HALSIM_GetAnalogGyroInitialized(i)) {
|
||||
ImGui::PushStyleColor(ImGuiCol_Text, IM_COL32(96, 96, 96, 255));
|
||||
ImGui::LabelText(name, "AnalogGyro[%d]", i);
|
||||
ImGui::PopStyleColor();
|
||||
} else if (auto simDevice = HALSIM_GetAnalogInSimDevice(i)) {
|
||||
ImGui::PushStyleColor(ImGuiCol_Text, IM_COL32(96, 96, 96, 255));
|
||||
ImGui::LabelText(name, "%s", HALSIM_GetSimDeviceName(simDevice));
|
||||
ImGui::PopStyleColor();
|
||||
} else {
|
||||
float val = HALSIM_GetAnalogInVoltage(i);
|
||||
if (ImGui::SliderFloat(name, &val, 0.0, 5.0))
|
||||
HALSIM_SetAnalogInVoltage(i, val);
|
||||
}
|
||||
}
|
||||
}
|
||||
if (!hasInputs) ImGui::Text("No analog inputs");
|
||||
}
|
||||
|
||||
void AnalogInputGui::Initialize() {
|
||||
HALSimGui::AddWindow("Analog Inputs", DisplayAnalogInputs,
|
||||
ImGuiWindowFlags_AlwaysAutoResize);
|
||||
HALSimGui::SetDefaultWindowPos("Analog Inputs", 640, 20);
|
||||
}
|
||||
17
simulation/halsim_gui/src/main/native/cpp/AnalogInputGui.h
Normal file
17
simulation/halsim_gui/src/main/native/cpp/AnalogInputGui.h
Normal file
@@ -0,0 +1,17 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
namespace halsimgui {
|
||||
|
||||
class AnalogInputGui {
|
||||
public:
|
||||
static void Initialize();
|
||||
};
|
||||
|
||||
} // namespace halsimgui
|
||||
47
simulation/halsim_gui/src/main/native/cpp/AnalogOutGui.cpp
Normal file
47
simulation/halsim_gui/src/main/native/cpp/AnalogOutGui.cpp
Normal file
@@ -0,0 +1,47 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "AnalogOutGui.h"
|
||||
|
||||
#include <cstdio>
|
||||
#include <cstring>
|
||||
#include <memory>
|
||||
|
||||
#include <hal/Ports.h>
|
||||
#include <imgui.h>
|
||||
#include <mockdata/AnalogOutData.h>
|
||||
|
||||
#include "SimDeviceGui.h"
|
||||
|
||||
using namespace halsimgui;
|
||||
|
||||
static void DisplayAnalogOutputs() {
|
||||
static const int numAnalog = HAL_GetNumAnalogOutputs();
|
||||
static auto init = std::make_unique<bool[]>(numAnalog);
|
||||
|
||||
int count = 0;
|
||||
for (int i = 0; i < numAnalog; ++i) {
|
||||
init[i] = HALSIM_GetAnalogOutInitialized(i);
|
||||
if (init[i]) ++count;
|
||||
}
|
||||
|
||||
if (count == 0) return;
|
||||
|
||||
if (SimDeviceGui::StartDevice("Analog Outputs")) {
|
||||
for (int i = 0; i < numAnalog; ++i) {
|
||||
if (!init[i]) continue;
|
||||
char name[32];
|
||||
std::snprintf(name, sizeof(name), "Out[%d]", i);
|
||||
HAL_Value value = HAL_MakeDouble(HALSIM_GetAnalogOutVoltage(i));
|
||||
SimDeviceGui::DisplayValue(name, true, &value);
|
||||
}
|
||||
|
||||
SimDeviceGui::FinishDevice();
|
||||
}
|
||||
}
|
||||
|
||||
void AnalogOutGui::Initialize() { SimDeviceGui::Add(DisplayAnalogOutputs); }
|
||||
17
simulation/halsim_gui/src/main/native/cpp/AnalogOutGui.h
Normal file
17
simulation/halsim_gui/src/main/native/cpp/AnalogOutGui.h
Normal file
@@ -0,0 +1,17 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
namespace halsimgui {
|
||||
|
||||
class AnalogOutGui {
|
||||
public:
|
||||
static void Initialize();
|
||||
};
|
||||
|
||||
} // namespace halsimgui
|
||||
59
simulation/halsim_gui/src/main/native/cpp/CompressorGui.cpp
Normal file
59
simulation/halsim_gui/src/main/native/cpp/CompressorGui.cpp
Normal file
@@ -0,0 +1,59 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "CompressorGui.h"
|
||||
|
||||
#include <cstdio>
|
||||
|
||||
#include <hal/Ports.h>
|
||||
#include <hal/Value.h>
|
||||
#include <imgui.h>
|
||||
#include <mockdata/PCMData.h>
|
||||
|
||||
#include "SimDeviceGui.h"
|
||||
|
||||
using namespace halsimgui;
|
||||
|
||||
static void DisplayCompressors() {
|
||||
static int numPcm = HAL_GetNumPCMModules();
|
||||
for (int i = 0; i < numPcm; ++i) {
|
||||
if (!HALSIM_GetPCMCompressorInitialized(i)) continue;
|
||||
char name[32];
|
||||
std::snprintf(name, sizeof(name), "Compressor[%d]", i);
|
||||
if (SimDeviceGui::StartDevice(name)) {
|
||||
HAL_Value value;
|
||||
|
||||
// enabled
|
||||
value = HAL_MakeBoolean(HALSIM_GetPCMCompressorOn(i));
|
||||
if (SimDeviceGui::DisplayValue("Running", false, &value))
|
||||
HALSIM_SetPCMCompressorOn(i, value.data.v_boolean);
|
||||
|
||||
// closed loop
|
||||
value = HAL_MakeEnum(HALSIM_GetPCMClosedLoopEnabled(i) ? 1 : 0);
|
||||
static const char* enabledOptions[] = {"disabled", "enabled"};
|
||||
if (SimDeviceGui::DisplayValue("Closed Loop", true, &value,
|
||||
enabledOptions, 2))
|
||||
HALSIM_SetPCMClosedLoopEnabled(i, value.data.v_enum);
|
||||
|
||||
// pressure switch
|
||||
value = HAL_MakeEnum(HALSIM_GetPCMPressureSwitch(i) ? 1 : 0);
|
||||
static const char* switchOptions[] = {"full", "low"};
|
||||
if (SimDeviceGui::DisplayValue("Pressure", false, &value, switchOptions,
|
||||
2))
|
||||
HALSIM_SetPCMPressureSwitch(i, value.data.v_enum);
|
||||
|
||||
// compressor current
|
||||
value = HAL_MakeDouble(HALSIM_GetPCMCompressorCurrent(i));
|
||||
if (SimDeviceGui::DisplayValue("Current (A)", false, &value))
|
||||
HALSIM_SetPCMCompressorCurrent(i, value.data.v_double);
|
||||
|
||||
SimDeviceGui::FinishDevice();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void CompressorGui::Initialize() { SimDeviceGui::Add(DisplayCompressors); }
|
||||
17
simulation/halsim_gui/src/main/native/cpp/CompressorGui.h
Normal file
17
simulation/halsim_gui/src/main/native/cpp/CompressorGui.h
Normal file
@@ -0,0 +1,17 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
namespace halsimgui {
|
||||
|
||||
class CompressorGui {
|
||||
public:
|
||||
static void Initialize();
|
||||
};
|
||||
|
||||
} // namespace halsimgui
|
||||
110
simulation/halsim_gui/src/main/native/cpp/DIOGui.cpp
Normal file
110
simulation/halsim_gui/src/main/native/cpp/DIOGui.cpp
Normal file
@@ -0,0 +1,110 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "DIOGui.h"
|
||||
|
||||
#include <cstdio>
|
||||
#include <cstring>
|
||||
#include <memory>
|
||||
|
||||
#include <hal/Ports.h>
|
||||
#include <imgui.h>
|
||||
#include <mockdata/DIOData.h>
|
||||
#include <mockdata/DigitalPWMData.h>
|
||||
#include <mockdata/EncoderData.h>
|
||||
#include <mockdata/SimDeviceData.h>
|
||||
|
||||
#include "HALSimGui.h"
|
||||
|
||||
using namespace halsimgui;
|
||||
|
||||
static void LabelSimDevice(const char* name, HAL_SimDeviceHandle simDevice) {
|
||||
ImGui::PushStyleColor(ImGuiCol_Text, IM_COL32(96, 96, 96, 255));
|
||||
ImGui::LabelText(name, "%s", HALSIM_GetSimDeviceName(simDevice));
|
||||
ImGui::PopStyleColor();
|
||||
}
|
||||
|
||||
static void DisplayDIO() {
|
||||
bool hasAny = false;
|
||||
static int numDIO = HAL_GetNumDigitalChannels();
|
||||
static int numPWM = HAL_GetNumDigitalPWMOutputs();
|
||||
static int numEncoder = HAL_GetNumEncoders();
|
||||
static auto pwmMap = std::make_unique<int[]>(numDIO);
|
||||
static auto encoderMap = std::make_unique<int[]>(numDIO);
|
||||
|
||||
std::memset(pwmMap.get(), 0, numDIO * sizeof(pwmMap[0]));
|
||||
std::memset(encoderMap.get(), 0, numDIO * sizeof(encoderMap[0]));
|
||||
|
||||
for (int i = 0; i < numPWM; ++i) {
|
||||
if (HALSIM_GetDigitalPWMInitialized(i)) {
|
||||
int channel = HALSIM_GetDigitalPWMPin(i);
|
||||
if (channel >= 0 && channel < numDIO) pwmMap[channel] = i + 1;
|
||||
}
|
||||
}
|
||||
|
||||
for (int i = 0; i < numEncoder; ++i) {
|
||||
if (HALSIM_GetEncoderInitialized(i)) {
|
||||
int channel;
|
||||
channel = HALSIM_GetEncoderDigitalChannelA(i);
|
||||
if (channel >= 0 && channel < numDIO) encoderMap[channel] = i + 1;
|
||||
channel = HALSIM_GetEncoderDigitalChannelB(i);
|
||||
if (channel >= 0 && channel < numDIO) encoderMap[channel] = i + 1;
|
||||
}
|
||||
}
|
||||
|
||||
ImGui::PushItemWidth(100);
|
||||
for (int i = 0; i < numDIO; ++i) {
|
||||
if (HALSIM_GetDIOInitialized(i)) {
|
||||
hasAny = true;
|
||||
char name[32];
|
||||
if (pwmMap[i] > 0) {
|
||||
std::snprintf(name, sizeof(name), "PWM[%d]", i);
|
||||
if (auto simDevice = HALSIM_GetDIOSimDevice(i)) {
|
||||
LabelSimDevice(name, simDevice);
|
||||
} else {
|
||||
ImGui::LabelText(name, "%0.3f",
|
||||
HALSIM_GetDigitalPWMDutyCycle(pwmMap[i] - 1));
|
||||
}
|
||||
} else if (encoderMap[i] > 0) {
|
||||
std::snprintf(name, sizeof(name), " In[%d]", i);
|
||||
if (auto simDevice = HALSIM_GetEncoderSimDevice(encoderMap[i] - 1)) {
|
||||
LabelSimDevice(name, simDevice);
|
||||
} else {
|
||||
ImGui::PushStyleColor(ImGuiCol_Text, IM_COL32(96, 96, 96, 255));
|
||||
ImGui::LabelText(name, "Encoder[%d,%d]",
|
||||
HALSIM_GetEncoderDigitalChannelA(encoderMap[i] - 1),
|
||||
HALSIM_GetEncoderDigitalChannelB(encoderMap[i] - 1));
|
||||
ImGui::PopStyleColor();
|
||||
}
|
||||
} else if (!HALSIM_GetDIOIsInput(i)) {
|
||||
std::snprintf(name, sizeof(name), "Out[%d]", i);
|
||||
if (auto simDevice = HALSIM_GetDIOSimDevice(i)) {
|
||||
LabelSimDevice(name, simDevice);
|
||||
} else {
|
||||
ImGui::LabelText(name, "%s",
|
||||
HALSIM_GetDIOValue(i) ? "1 (high)" : "0 (low)");
|
||||
}
|
||||
} else {
|
||||
std::snprintf(name, sizeof(name), " In[%d]", i);
|
||||
if (auto simDevice = HALSIM_GetDIOSimDevice(i)) {
|
||||
LabelSimDevice(name, simDevice);
|
||||
} else {
|
||||
static const char* options[] = {"0 (low)", "1 (high)"};
|
||||
int val = HALSIM_GetDIOValue(i) ? 1 : 0;
|
||||
if (ImGui::Combo(name, &val, options, 2)) HALSIM_SetDIOValue(i, val);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
ImGui::PopItemWidth();
|
||||
if (!hasAny) ImGui::Text("No Digital I/O");
|
||||
}
|
||||
|
||||
void DIOGui::Initialize() {
|
||||
HALSimGui::AddWindow("DIO", DisplayDIO, ImGuiWindowFlags_AlwaysAutoResize);
|
||||
HALSimGui::SetDefaultWindowPos("DIO", 470, 20);
|
||||
}
|
||||
17
simulation/halsim_gui/src/main/native/cpp/DIOGui.h
Normal file
17
simulation/halsim_gui/src/main/native/cpp/DIOGui.h
Normal file
@@ -0,0 +1,17 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
namespace halsimgui {
|
||||
|
||||
class DIOGui {
|
||||
public:
|
||||
static void Initialize();
|
||||
};
|
||||
|
||||
} // namespace halsimgui
|
||||
502
simulation/halsim_gui/src/main/native/cpp/DriverStationGui.cpp
Normal file
502
simulation/halsim_gui/src/main/native/cpp/DriverStationGui.cpp
Normal file
@@ -0,0 +1,502 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "DriverStationGui.h"
|
||||
|
||||
#include <cstring>
|
||||
#include <string>
|
||||
|
||||
#include <GLFW/glfw3.h>
|
||||
#include <imgui.h>
|
||||
#include <imgui_internal.h>
|
||||
#include <mockdata/DriverStationData.h>
|
||||
#include <wpi/Format.h>
|
||||
#include <wpi/SmallString.h>
|
||||
#include <wpi/StringRef.h>
|
||||
#include <wpi/raw_ostream.h>
|
||||
|
||||
#include "ExtraGuiWidgets.h"
|
||||
#include "HALSimGui.h"
|
||||
|
||||
using namespace halsimgui;
|
||||
|
||||
namespace {
|
||||
|
||||
struct SystemJoystick {
|
||||
bool present = false;
|
||||
int axisCount = 0;
|
||||
const float* axes = nullptr;
|
||||
int buttonCount = 0;
|
||||
const unsigned char* buttons = nullptr;
|
||||
int hatCount = 0;
|
||||
const unsigned char* hats = nullptr;
|
||||
const char* name = nullptr;
|
||||
bool isGamepad = false;
|
||||
GLFWgamepadstate gamepadState;
|
||||
|
||||
bool anyButtonPressed = false;
|
||||
|
||||
void Update(int i);
|
||||
};
|
||||
|
||||
struct RobotJoystick {
|
||||
std::string guid;
|
||||
const SystemJoystick* sys = nullptr;
|
||||
bool useGamepad = false;
|
||||
|
||||
HAL_JoystickDescriptor desc;
|
||||
HAL_JoystickAxes axes;
|
||||
HAL_JoystickButtons buttons;
|
||||
HAL_JoystickPOVs povs;
|
||||
|
||||
void Update();
|
||||
void SetHAL(int i);
|
||||
bool IsButtonPressed(int i) { return (buttons.buttons & (1u << i)) != 0; }
|
||||
};
|
||||
|
||||
} // namespace
|
||||
|
||||
// system joysticks
|
||||
static SystemJoystick gSystemJoysticks[GLFW_JOYSTICK_LAST + 1];
|
||||
static int gNumSystemJoysticks = 0;
|
||||
|
||||
// robot joysticks
|
||||
static RobotJoystick gRobotJoysticks[HAL_kMaxJoysticks];
|
||||
|
||||
static bool gDisableDS = false;
|
||||
|
||||
// read/write joystick mapping to ini file
|
||||
static void* JoystickReadOpen(ImGuiContext* ctx, ImGuiSettingsHandler* handler,
|
||||
const char* name) {
|
||||
int num;
|
||||
if (wpi::StringRef{name}.getAsInteger(10, num)) return nullptr;
|
||||
if (num < 0 || num >= HAL_kMaxJoysticks) return nullptr;
|
||||
return &gRobotJoysticks[num];
|
||||
}
|
||||
|
||||
static void JoystickReadLine(ImGuiContext* ctx, ImGuiSettingsHandler* handler,
|
||||
void* entry, const char* lineStr) {
|
||||
RobotJoystick* joy = static_cast<RobotJoystick*>(entry);
|
||||
// format: guid=guid or useGamepad=0/1
|
||||
wpi::StringRef line{lineStr};
|
||||
auto [name, value] = line.split('=');
|
||||
name = name.trim();
|
||||
value = value.trim();
|
||||
if (name == "guid") {
|
||||
joy->guid = value;
|
||||
} else if (name == "useGamepad") {
|
||||
int num;
|
||||
if (value.getAsInteger(10, num)) return;
|
||||
joy->useGamepad = num;
|
||||
}
|
||||
}
|
||||
|
||||
static void JoystickWriteAll(ImGuiContext* ctx, ImGuiSettingsHandler* handler,
|
||||
ImGuiTextBuffer* out_buf) {
|
||||
for (int i = 0; i < HAL_kMaxJoysticks; ++i) {
|
||||
auto& joy = gRobotJoysticks[i];
|
||||
if (!joy.sys) continue;
|
||||
const char* guid = glfwGetJoystickGUID(joy.sys - gSystemJoysticks);
|
||||
if (!guid) continue;
|
||||
out_buf->appendf("[Joystick][%d]\nguid=%s\nuseGamepad=%d\n\n", i, guid,
|
||||
joy.useGamepad ? 1 : 0);
|
||||
}
|
||||
}
|
||||
|
||||
// read/write DS settings to ini file
|
||||
static void* DriverStationReadOpen(ImGuiContext* ctx,
|
||||
ImGuiSettingsHandler* handler,
|
||||
const char* name) {
|
||||
if (name == wpi::StringRef{"Main"}) return &gDisableDS;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
static void DriverStationReadLine(ImGuiContext* ctx,
|
||||
ImGuiSettingsHandler* handler, void* entry,
|
||||
const char* lineStr) {
|
||||
wpi::StringRef line{lineStr};
|
||||
auto [name, value] = line.split('=');
|
||||
name = name.trim();
|
||||
value = value.trim();
|
||||
if (name == "disable") {
|
||||
int num;
|
||||
if (value.getAsInteger(10, num)) return;
|
||||
gDisableDS = num;
|
||||
}
|
||||
}
|
||||
|
||||
static void DriverStationWriteAll(ImGuiContext* ctx,
|
||||
ImGuiSettingsHandler* handler,
|
||||
ImGuiTextBuffer* out_buf) {
|
||||
out_buf->appendf("[DriverStation][Main]\ndisable=%d\n\n", gDisableDS ? 1 : 0);
|
||||
}
|
||||
|
||||
void SystemJoystick::Update(int i) {
|
||||
bool wasPresent = present;
|
||||
present = glfwJoystickPresent(i);
|
||||
|
||||
if (!present) return;
|
||||
axes = glfwGetJoystickAxes(i, &axisCount);
|
||||
buttons = glfwGetJoystickButtons(i, &buttonCount);
|
||||
hats = glfwGetJoystickHats(i, &hatCount);
|
||||
isGamepad = glfwGetGamepadState(i, &gamepadState);
|
||||
|
||||
anyButtonPressed = false;
|
||||
for (int j = 0; j < buttonCount; ++j) {
|
||||
if (buttons[j]) {
|
||||
anyButtonPressed = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
for (int j = 0; j < hatCount; ++j) {
|
||||
if (hats[j] != GLFW_HAT_CENTERED) {
|
||||
anyButtonPressed = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (!present || wasPresent) return;
|
||||
name = glfwGetJoystickName(i);
|
||||
|
||||
// try to find matching GUID
|
||||
if (const char* guid = glfwGetJoystickGUID(i)) {
|
||||
for (auto&& joy : gRobotJoysticks) {
|
||||
if (guid == joy.guid) {
|
||||
joy.sys = &gSystemJoysticks[i];
|
||||
joy.guid.clear();
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static int HatToAngle(unsigned char hat) {
|
||||
switch (hat) {
|
||||
case GLFW_HAT_UP:
|
||||
return 0;
|
||||
case GLFW_HAT_RIGHT:
|
||||
return 90;
|
||||
case GLFW_HAT_DOWN:
|
||||
return 180;
|
||||
case GLFW_HAT_LEFT:
|
||||
return 270;
|
||||
case GLFW_HAT_RIGHT_UP:
|
||||
return 45;
|
||||
case GLFW_HAT_RIGHT_DOWN:
|
||||
return 135;
|
||||
case GLFW_HAT_LEFT_UP:
|
||||
return 315;
|
||||
case GLFW_HAT_LEFT_DOWN:
|
||||
return 225;
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
void RobotJoystick::Update() {
|
||||
std::memset(&desc, 0, sizeof(desc));
|
||||
desc.type = -1;
|
||||
std::memset(&axes, 0, sizeof(axes));
|
||||
std::memset(&buttons, 0, sizeof(buttons));
|
||||
std::memset(&povs, 0, sizeof(povs));
|
||||
|
||||
if (!sys || !sys->present) return;
|
||||
|
||||
// use gamepad mappings if present and enabled
|
||||
const float* sysAxes;
|
||||
const unsigned char* sysButtons;
|
||||
if (sys->isGamepad && useGamepad) {
|
||||
sysAxes = sys->gamepadState.axes;
|
||||
sysButtons = sys->gamepadState.buttons;
|
||||
} else {
|
||||
sysAxes = sys->axes;
|
||||
sysButtons = sys->buttons;
|
||||
}
|
||||
|
||||
// copy into HAL structures
|
||||
desc.isXbox = sys->isGamepad ? 1 : 0;
|
||||
desc.type = sys->isGamepad ? 21 : 20;
|
||||
std::strncpy(desc.name, sys->name, 256);
|
||||
desc.axisCount = (std::min)(sys->axisCount, HAL_kMaxJoystickAxes);
|
||||
// desc.axisTypes ???
|
||||
desc.buttonCount = (std::min)(sys->buttonCount, 32);
|
||||
desc.povCount = (std::min)(sys->hatCount, HAL_kMaxJoystickPOVs);
|
||||
|
||||
axes.count = desc.axisCount;
|
||||
std::memcpy(axes.axes, sysAxes, axes.count * sizeof(&axes.axes[0]));
|
||||
|
||||
buttons.count = desc.buttonCount;
|
||||
for (int j = 0; j < buttons.count; ++j)
|
||||
buttons.buttons |= (sysButtons[j] ? 1u : 0u) << j;
|
||||
|
||||
povs.count = desc.povCount;
|
||||
for (int j = 0; j < povs.count; ++j) povs.povs[j] = HatToAngle(sys->hats[j]);
|
||||
}
|
||||
|
||||
void RobotJoystick::SetHAL(int i) {
|
||||
// set at HAL level
|
||||
HALSIM_SetJoystickDescriptor(i, &desc);
|
||||
HALSIM_SetJoystickAxes(i, &axes);
|
||||
HALSIM_SetJoystickButtons(i, &buttons);
|
||||
HALSIM_SetJoystickPOVs(i, &povs);
|
||||
}
|
||||
|
||||
static void DriverStationExecute() {
|
||||
static bool prevDisableDS = false;
|
||||
if (gDisableDS && !prevDisableDS) {
|
||||
HALSimGui::SetWindowVisibility("FMS", HALSimGui::kDisabled);
|
||||
HALSimGui::SetWindowVisibility("System Joysticks", HALSimGui::kDisabled);
|
||||
HALSimGui::SetWindowVisibility("Joysticks", HALSimGui::kDisabled);
|
||||
} else if (!gDisableDS && prevDisableDS) {
|
||||
HALSimGui::SetWindowVisibility("FMS", HALSimGui::kShow);
|
||||
HALSimGui::SetWindowVisibility("System Joysticks", HALSimGui::kShow);
|
||||
HALSimGui::SetWindowVisibility("Joysticks", HALSimGui::kShow);
|
||||
}
|
||||
prevDisableDS = gDisableDS;
|
||||
if (gDisableDS) return;
|
||||
|
||||
double curTime = glfwGetTime();
|
||||
|
||||
// update system joysticks
|
||||
for (int i = 0; i <= GLFW_JOYSTICK_LAST; ++i) {
|
||||
gSystemJoysticks[i].Update(i);
|
||||
if (gSystemJoysticks[i].present) gNumSystemJoysticks = i + 1;
|
||||
}
|
||||
|
||||
// update robot joysticks
|
||||
for (auto&& joy : gRobotJoysticks) joy.Update();
|
||||
|
||||
bool isEnabled = HALSIM_GetDriverStationEnabled();
|
||||
bool isAuto = HALSIM_GetDriverStationAutonomous();
|
||||
bool isTest = HALSIM_GetDriverStationTest();
|
||||
|
||||
// Robot state
|
||||
{
|
||||
ImGui::SetNextWindowPos(ImVec2{5, 20}, ImGuiCond_FirstUseEver);
|
||||
ImGui::Begin("Robot State", nullptr, ImGuiWindowFlags_AlwaysAutoResize);
|
||||
if (ImGui::Selectable("Disabled", !isEnabled))
|
||||
HALSIM_SetDriverStationEnabled(false);
|
||||
if (ImGui::Selectable("Autonomous", isEnabled && isAuto && !isTest)) {
|
||||
HALSIM_SetDriverStationAutonomous(true);
|
||||
HALSIM_SetDriverStationTest(false);
|
||||
HALSIM_SetDriverStationEnabled(true);
|
||||
}
|
||||
if (ImGui::Selectable("Teleoperated", isEnabled && !isAuto && !isTest)) {
|
||||
HALSIM_SetDriverStationAutonomous(false);
|
||||
HALSIM_SetDriverStationTest(false);
|
||||
HALSIM_SetDriverStationEnabled(true);
|
||||
}
|
||||
if (ImGui::Selectable("Test", isEnabled && isTest)) {
|
||||
HALSIM_SetDriverStationAutonomous(false);
|
||||
HALSIM_SetDriverStationTest(true);
|
||||
HALSIM_SetDriverStationEnabled(true);
|
||||
}
|
||||
ImGui::End();
|
||||
}
|
||||
|
||||
// Update HAL
|
||||
for (int i = 0; i < HAL_kMaxJoysticks; ++i) gRobotJoysticks[i].SetHAL(i);
|
||||
|
||||
// Send new data every 20 ms (may be slower depending on GUI refresh rate)
|
||||
static double lastNewDataTime = 0.0;
|
||||
if ((curTime - lastNewDataTime) > 0.02) {
|
||||
lastNewDataTime = curTime;
|
||||
HALSIM_NotifyDriverStationNewData();
|
||||
}
|
||||
}
|
||||
|
||||
static void DisplayFMS() {
|
||||
double curTime = glfwGetTime();
|
||||
|
||||
// FMS Attached
|
||||
bool fmsAttached = HALSIM_GetDriverStationFmsAttached();
|
||||
if (ImGui::Checkbox("FMS Attached", &fmsAttached))
|
||||
HALSIM_SetDriverStationFmsAttached(fmsAttached);
|
||||
|
||||
// DS Attached
|
||||
bool dsAttached = HALSIM_GetDriverStationDsAttached();
|
||||
if (ImGui::Checkbox("DS Attached", &dsAttached))
|
||||
HALSIM_SetDriverStationDsAttached(dsAttached);
|
||||
|
||||
// Alliance Station
|
||||
static const char* stations[] = {"Red 1", "Red 2", "Red 3",
|
||||
"Blue 1", "Blue 2", "Blue 3"};
|
||||
int allianceStationId = HALSIM_GetDriverStationAllianceStationId();
|
||||
ImGui::SetNextItemWidth(100);
|
||||
if (ImGui::Combo("Alliance Station", &allianceStationId, stations, 6))
|
||||
HALSIM_SetDriverStationAllianceStationId(
|
||||
static_cast<HAL_AllianceStationID>(allianceStationId));
|
||||
|
||||
// Match Time
|
||||
static bool matchTimeEnabled = true;
|
||||
ImGui::Checkbox("Match Time Enabled", &matchTimeEnabled);
|
||||
|
||||
static double startMatchTime = 0.0;
|
||||
double matchTime = HALSIM_GetDriverStationMatchTime();
|
||||
ImGui::SetNextItemWidth(100);
|
||||
if (ImGui::InputDouble("Match Time", &matchTime, 0, 0, "%.1f",
|
||||
ImGuiInputTextFlags_EnterReturnsTrue)) {
|
||||
HALSIM_SetDriverStationMatchTime(matchTime);
|
||||
startMatchTime = curTime - matchTime;
|
||||
} else if (!HALSIM_GetDriverStationEnabled()) {
|
||||
startMatchTime = curTime - matchTime;
|
||||
} else if (matchTimeEnabled) {
|
||||
HALSIM_SetDriverStationMatchTime(curTime - startMatchTime);
|
||||
}
|
||||
ImGui::SameLine();
|
||||
if (ImGui::Button("Reset")) {
|
||||
HALSIM_SetDriverStationMatchTime(0.0);
|
||||
startMatchTime = curTime;
|
||||
}
|
||||
|
||||
// Game Specific Message
|
||||
static HAL_MatchInfo matchInfo;
|
||||
ImGui::SetNextItemWidth(100);
|
||||
if (ImGui::InputText("Game Specific",
|
||||
reinterpret_cast<char*>(matchInfo.gameSpecificMessage),
|
||||
sizeof(matchInfo.gameSpecificMessage),
|
||||
ImGuiInputTextFlags_EnterReturnsTrue)) {
|
||||
matchInfo.gameSpecificMessageSize =
|
||||
std::strlen(reinterpret_cast<char*>(matchInfo.gameSpecificMessage));
|
||||
HALSIM_SetMatchInfo(&matchInfo);
|
||||
}
|
||||
}
|
||||
|
||||
static void DisplaySystemJoysticks() {
|
||||
ImGui::Text("(Drag and drop to Joysticks)");
|
||||
int numShowJoysticks = gNumSystemJoysticks < 6 ? 6 : gNumSystemJoysticks;
|
||||
for (int i = 0; i < numShowJoysticks; ++i) {
|
||||
auto& joy = gSystemJoysticks[i];
|
||||
wpi::SmallString<128> label;
|
||||
wpi::raw_svector_ostream os(label);
|
||||
os << wpi::format("%d: %s", i, joy.name);
|
||||
|
||||
// highlight if any buttons pressed
|
||||
if (joy.anyButtonPressed)
|
||||
ImGui::PushStyleColor(ImGuiCol_Text, IM_COL32(255, 255, 0, 255));
|
||||
ImGui::Selectable(label.c_str(), false,
|
||||
joy.present ? ImGuiSelectableFlags_None
|
||||
: ImGuiSelectableFlags_Disabled);
|
||||
if (joy.anyButtonPressed) ImGui::PopStyleColor();
|
||||
|
||||
// drag and drop sources are the low level joysticks
|
||||
if (ImGui::BeginDragDropSource()) {
|
||||
SystemJoystick* joyPtr = &joy;
|
||||
ImGui::SetDragDropPayload("Joystick", &joyPtr, sizeof(joyPtr));
|
||||
ImGui::Text("%d: %s", i, joy.name);
|
||||
ImGui::EndDragDropSource();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void DisplayJoysticks() {
|
||||
// imgui doesn't size columns properly with autoresize, so force it
|
||||
ImGui::Dummy(ImVec2(14.0 * 9 * HAL_kMaxJoysticks, 0));
|
||||
|
||||
ImGui::Columns(HAL_kMaxJoysticks, "Joysticks", false);
|
||||
for (int i = 0; i < HAL_kMaxJoysticks; ++i) {
|
||||
auto& joy = gRobotJoysticks[i];
|
||||
char label[30];
|
||||
std::snprintf(label, sizeof(label), "Joystick %d", i);
|
||||
if (joy.sys) {
|
||||
ImGui::Selectable(label, false);
|
||||
if (ImGui::BeginDragDropSource()) {
|
||||
ImGui::SetDragDropPayload("Joystick", &joy.sys, sizeof(joy.sys));
|
||||
ImGui::Text("%d: %s", static_cast<int>(joy.sys - gSystemJoysticks),
|
||||
joy.sys->name);
|
||||
ImGui::EndDragDropSource();
|
||||
}
|
||||
} else {
|
||||
ImGui::Selectable(label, false, ImGuiSelectableFlags_Disabled);
|
||||
}
|
||||
if (ImGui::BeginDragDropTarget()) {
|
||||
if (const ImGuiPayload* payload =
|
||||
ImGui::AcceptDragDropPayload("Joystick")) {
|
||||
IM_ASSERT(payload->DataSize == sizeof(SystemJoystick*));
|
||||
SystemJoystick* payload_sys =
|
||||
*static_cast<SystemJoystick* const*>(payload->Data);
|
||||
// clear it from the other joysticks
|
||||
for (auto&& joy2 : gRobotJoysticks) {
|
||||
if (joy2.sys == payload_sys) joy2.sys = nullptr;
|
||||
}
|
||||
joy.sys = payload_sys;
|
||||
joy.guid.clear();
|
||||
joy.useGamepad = false;
|
||||
}
|
||||
ImGui::EndDragDropTarget();
|
||||
}
|
||||
ImGui::NextColumn();
|
||||
}
|
||||
ImGui::Separator();
|
||||
|
||||
for (int i = 0; i < HAL_kMaxJoysticks; ++i) {
|
||||
auto& joy = gRobotJoysticks[i];
|
||||
|
||||
if (joy.sys && joy.sys->present) {
|
||||
// update GUI display
|
||||
ImGui::PushID(i);
|
||||
ImGui::Text("%d: %s", static_cast<int>(joy.sys - gSystemJoysticks),
|
||||
joy.sys->name);
|
||||
|
||||
if (joy.sys->isGamepad) ImGui::Checkbox("Map gamepad", &joy.useGamepad);
|
||||
|
||||
for (int j = 0; j < joy.axes.count; ++j)
|
||||
ImGui::Text("Axis[%d]: %.3f", j, joy.axes.axes[j]);
|
||||
|
||||
for (int j = 0; j < joy.povs.count; ++j)
|
||||
ImGui::Text("POVs[%d]: %d", j, joy.povs.povs[j]);
|
||||
|
||||
// show buttons as multiple lines of LED indicators, 8 per line
|
||||
static const ImU32 color = IM_COL32(255, 255, 102, 255);
|
||||
wpi::SmallVector<int, 64> buttons;
|
||||
buttons.resize(joy.buttons.count);
|
||||
for (int j = 0; j < joy.buttons.count; ++j)
|
||||
buttons[j] = joy.IsButtonPressed(j) ? 1 : -1;
|
||||
DrawLEDs(buttons.data(), buttons.size(), 8, &color);
|
||||
ImGui::PopID();
|
||||
} else {
|
||||
ImGui::Text("Unassigned");
|
||||
}
|
||||
ImGui::NextColumn();
|
||||
}
|
||||
ImGui::Columns(1);
|
||||
}
|
||||
|
||||
static void DriverStationOptionMenu() {
|
||||
ImGui::MenuItem("Turn off DS", nullptr, &gDisableDS);
|
||||
}
|
||||
|
||||
void DriverStationGui::Initialize() {
|
||||
// hook ini handler to save joystick settings
|
||||
ImGuiSettingsHandler iniHandler;
|
||||
iniHandler.TypeName = "Joystick";
|
||||
iniHandler.TypeHash = ImHashStr(iniHandler.TypeName);
|
||||
iniHandler.ReadOpenFn = JoystickReadOpen;
|
||||
iniHandler.ReadLineFn = JoystickReadLine;
|
||||
iniHandler.WriteAllFn = JoystickWriteAll;
|
||||
ImGui::GetCurrentContext()->SettingsHandlers.push_back(iniHandler);
|
||||
|
||||
// hook ini handler to save DS settings
|
||||
iniHandler.TypeName = "DriverStation";
|
||||
iniHandler.TypeHash = ImHashStr(iniHandler.TypeName);
|
||||
iniHandler.ReadOpenFn = DriverStationReadOpen;
|
||||
iniHandler.ReadLineFn = DriverStationReadLine;
|
||||
iniHandler.WriteAllFn = DriverStationWriteAll;
|
||||
ImGui::GetCurrentContext()->SettingsHandlers.push_back(iniHandler);
|
||||
|
||||
HALSimGui::AddExecute(DriverStationExecute);
|
||||
HALSimGui::AddWindow("FMS", DisplayFMS, ImGuiWindowFlags_AlwaysAutoResize);
|
||||
HALSimGui::AddWindow("System Joysticks", DisplaySystemJoysticks,
|
||||
ImGuiWindowFlags_AlwaysAutoResize);
|
||||
HALSimGui::AddWindow("Joysticks", DisplayJoysticks,
|
||||
ImGuiWindowFlags_AlwaysAutoResize);
|
||||
HALSimGui::AddOptionMenu(DriverStationOptionMenu);
|
||||
|
||||
HALSimGui::SetDefaultWindowPos("FMS", 5, 540);
|
||||
HALSimGui::SetDefaultWindowPos("System Joysticks", 5, 385);
|
||||
HALSimGui::SetDefaultWindowPos("Joysticks", 250, 465);
|
||||
}
|
||||
17
simulation/halsim_gui/src/main/native/cpp/DriverStationGui.h
Normal file
17
simulation/halsim_gui/src/main/native/cpp/DriverStationGui.h
Normal file
@@ -0,0 +1,17 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
namespace halsimgui {
|
||||
|
||||
class DriverStationGui {
|
||||
public:
|
||||
static void Initialize();
|
||||
};
|
||||
|
||||
} // namespace halsimgui
|
||||
129
simulation/halsim_gui/src/main/native/cpp/EncoderGui.cpp
Normal file
129
simulation/halsim_gui/src/main/native/cpp/EncoderGui.cpp
Normal file
@@ -0,0 +1,129 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "EncoderGui.h"
|
||||
|
||||
#include <cstdio>
|
||||
|
||||
#include <hal/Ports.h>
|
||||
#include <imgui.h>
|
||||
#include <imgui_internal.h>
|
||||
#include <mockdata/EncoderData.h>
|
||||
#include <mockdata/SimDeviceData.h>
|
||||
#include <wpi/DenseMap.h>
|
||||
#include <wpi/StringRef.h>
|
||||
|
||||
#include "HALSimGui.h"
|
||||
|
||||
using namespace halsimgui;
|
||||
|
||||
static wpi::DenseMap<int, bool> gEncodersOpen; // indexed by channel A
|
||||
|
||||
// read/write open state to ini file
|
||||
static void* EncodersReadOpen(ImGuiContext* ctx, ImGuiSettingsHandler* handler,
|
||||
const char* name) {
|
||||
int num;
|
||||
if (wpi::StringRef{name}.getAsInteger(10, num)) return nullptr;
|
||||
return &gEncodersOpen[num];
|
||||
}
|
||||
|
||||
static void EncodersReadLine(ImGuiContext* ctx, ImGuiSettingsHandler* handler,
|
||||
void* entry, const char* lineStr) {
|
||||
bool* element = static_cast<bool*>(entry);
|
||||
wpi::StringRef line{lineStr};
|
||||
auto [name, value] = line.split('=');
|
||||
name = name.trim();
|
||||
value = value.trim();
|
||||
if (name == "open") {
|
||||
int num;
|
||||
if (value.getAsInteger(10, num)) return;
|
||||
*element = num;
|
||||
}
|
||||
}
|
||||
|
||||
static void EncodersWriteAll(ImGuiContext* ctx, ImGuiSettingsHandler* handler,
|
||||
ImGuiTextBuffer* out_buf) {
|
||||
for (auto it : gEncodersOpen)
|
||||
out_buf->appendf("[Encoder][%d]\nopen=%d\n\n", it.first, it.second ? 1 : 0);
|
||||
}
|
||||
|
||||
static void DisplayEncoders() {
|
||||
bool hasAny = false;
|
||||
static int numEncoder = HAL_GetNumEncoders();
|
||||
ImGui::PushItemWidth(100);
|
||||
for (int i = 0; i < numEncoder; ++i) {
|
||||
if (HALSIM_GetEncoderInitialized(i)) {
|
||||
hasAny = true;
|
||||
char name[32];
|
||||
int chA = HALSIM_GetEncoderDigitalChannelA(i);
|
||||
int chB = HALSIM_GetEncoderDigitalChannelB(i);
|
||||
std::snprintf(name, sizeof(name), "Encoder[%d,%d]", chA, chB);
|
||||
if (auto simDevice = HALSIM_GetEncoderSimDevice(i)) {
|
||||
ImGui::PushStyleColor(ImGuiCol_Text, IM_COL32(96, 96, 96, 255));
|
||||
ImGui::Text("%s", HALSIM_GetSimDeviceName(simDevice));
|
||||
ImGui::PopStyleColor();
|
||||
} else if (ImGui::CollapsingHeader(
|
||||
name,
|
||||
gEncodersOpen[chA] ? ImGuiTreeNodeFlags_DefaultOpen : 0)) {
|
||||
gEncodersOpen[chA] = true;
|
||||
|
||||
ImGui::PushID(i);
|
||||
|
||||
// distance per pulse
|
||||
double distancePerPulse = HALSIM_GetEncoderDistancePerPulse(i);
|
||||
ImGui::LabelText("Dist/Count", "%.6f", distancePerPulse);
|
||||
|
||||
// count
|
||||
int count = HALSIM_GetEncoderCount(i);
|
||||
if (ImGui::InputInt("Count", &count)) HALSIM_SetEncoderCount(i, count);
|
||||
ImGui::SameLine();
|
||||
if (ImGui::Button("Reset")) HALSIM_SetEncoderCount(i, 0);
|
||||
|
||||
// max period
|
||||
double maxPeriod = HALSIM_GetEncoderMaxPeriod(i);
|
||||
ImGui::LabelText("Max Period", "%.6f", maxPeriod);
|
||||
|
||||
// period
|
||||
double period = HALSIM_GetEncoderPeriod(i);
|
||||
if (ImGui::InputDouble("Period", &period, 0, 0, "%.6g"))
|
||||
HALSIM_SetEncoderPeriod(i, period);
|
||||
|
||||
// reverse direction
|
||||
ImGui::LabelText(
|
||||
"Reverse Direction", "%s",
|
||||
HALSIM_GetEncoderReverseDirection(i) ? "true" : "false");
|
||||
|
||||
// direction
|
||||
static const char* options[] = {"reverse", "forward"};
|
||||
int direction = HALSIM_GetEncoderDirection(i) ? 1 : 0;
|
||||
if (ImGui::Combo("Direction", &direction, options, 2))
|
||||
HALSIM_SetEncoderDirection(i, direction);
|
||||
|
||||
ImGui::PopID();
|
||||
} else {
|
||||
gEncodersOpen[chA] = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
ImGui::PopItemWidth();
|
||||
if (!hasAny) ImGui::Text("No encoders");
|
||||
}
|
||||
|
||||
void EncoderGui::Initialize() {
|
||||
// hook ini handler to save settings
|
||||
ImGuiSettingsHandler iniHandler;
|
||||
iniHandler.TypeName = "Encoder";
|
||||
iniHandler.TypeHash = ImHashStr(iniHandler.TypeName);
|
||||
iniHandler.ReadOpenFn = EncodersReadOpen;
|
||||
iniHandler.ReadLineFn = EncodersReadLine;
|
||||
iniHandler.WriteAllFn = EncodersWriteAll;
|
||||
ImGui::GetCurrentContext()->SettingsHandlers.push_back(iniHandler);
|
||||
|
||||
HALSimGui::AddWindow("Encoders", DisplayEncoders,
|
||||
ImGuiWindowFlags_AlwaysAutoResize);
|
||||
HALSimGui::SetDefaultWindowPos("Encoders", 640, 215);
|
||||
}
|
||||
17
simulation/halsim_gui/src/main/native/cpp/EncoderGui.h
Normal file
17
simulation/halsim_gui/src/main/native/cpp/EncoderGui.h
Normal file
@@ -0,0 +1,17 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
namespace halsimgui {
|
||||
|
||||
class EncoderGui {
|
||||
public:
|
||||
static void Initialize();
|
||||
};
|
||||
|
||||
} // namespace halsimgui
|
||||
@@ -0,0 +1,37 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "ExtraGuiWidgets.h"
|
||||
|
||||
namespace halsimgui {
|
||||
|
||||
void DrawLEDs(int* values, int numValues, int cols, const ImU32* colors,
|
||||
float size, float spacing) {
|
||||
if (numValues == 0) return;
|
||||
|
||||
ImDrawList* drawList = ImGui::GetWindowDrawList();
|
||||
const ImVec2 p = ImGui::GetCursorScreenPos();
|
||||
float x = p.x + size / 2, y = p.y + size / 2;
|
||||
int rows = 1;
|
||||
for (int i = 0; i < numValues; ++i) {
|
||||
if (i >= (rows * cols)) {
|
||||
++rows;
|
||||
x = p.x + size / 2;
|
||||
y += size + spacing;
|
||||
}
|
||||
if (values[i] > 0)
|
||||
drawList->AddRectFilled(ImVec2(x, y), ImVec2(x + size, y + size),
|
||||
colors[values[i] - 1]);
|
||||
else if (values[i] < 0)
|
||||
drawList->AddRect(ImVec2(x, y), ImVec2(x + size, y + size),
|
||||
colors[-values[i] - 1], 0.0f, 0, 1.0);
|
||||
x += size + spacing;
|
||||
}
|
||||
ImGui::Dummy(ImVec2((size + spacing) * cols, (size + spacing) * rows));
|
||||
}
|
||||
|
||||
} // namespace halsimgui
|
||||
397
simulation/halsim_gui/src/main/native/cpp/HALSimGui.cpp
Normal file
397
simulation/halsim_gui/src/main/native/cpp/HALSimGui.cpp
Normal file
@@ -0,0 +1,397 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "HALSimGui.h"
|
||||
|
||||
#include <algorithm>
|
||||
#include <atomic>
|
||||
|
||||
#include <GL/gl3w.h>
|
||||
#include <GLFW/glfw3.h>
|
||||
#include <imgui.h>
|
||||
#include <imgui_impl_glfw.h>
|
||||
#include <imgui_impl_opengl3.h>
|
||||
#include <imgui_internal.h>
|
||||
#include <wpi/StringMap.h>
|
||||
#include <wpi/raw_ostream.h>
|
||||
|
||||
using namespace halsimgui;
|
||||
|
||||
namespace {
|
||||
struct WindowInfo {
|
||||
WindowInfo() = default;
|
||||
explicit WindowInfo(const char* name_) : name{name_} {}
|
||||
WindowInfo(const char* name_, std::function<void()> display_,
|
||||
ImGuiWindowFlags flags_)
|
||||
: name{name_}, display{std::move(display_)}, flags{flags_} {}
|
||||
|
||||
std::string name;
|
||||
std::function<void()> display;
|
||||
ImGuiWindowFlags flags = 0;
|
||||
bool visible = true;
|
||||
bool enabled = true;
|
||||
ImGuiCond posCond = 0;
|
||||
ImGuiCond sizeCond = 0;
|
||||
ImVec2 pos;
|
||||
ImVec2 size;
|
||||
};
|
||||
} // namespace
|
||||
|
||||
static std::atomic_bool gExit{false};
|
||||
static GLFWwindow* gWindow;
|
||||
static std::vector<std::function<void()>> gInitializers;
|
||||
static std::vector<std::function<void()>> gExecutors;
|
||||
static std::vector<WindowInfo> gWindows;
|
||||
static wpi::StringMap<int> gWindowMap; // index into gWindows
|
||||
static std::vector<int> gSortedWindows; // index into gWindows
|
||||
static std::vector<std::function<void()>> gOptionMenus;
|
||||
static std::vector<std::function<void()>> gMenus;
|
||||
|
||||
static void glfw_error_callback(int error, const char* description) {
|
||||
wpi::errs() << "GLFW Error " << error << ": " << description << '\n';
|
||||
}
|
||||
|
||||
// read/write open state to ini file
|
||||
static void* SimWindowsReadOpen(ImGuiContext* ctx,
|
||||
ImGuiSettingsHandler* handler,
|
||||
const char* name) {
|
||||
int index = gWindowMap.try_emplace(name, gWindows.size()).first->second;
|
||||
if (index == static_cast<int>(gWindows.size())) {
|
||||
gSortedWindows.push_back(index);
|
||||
gWindows.emplace_back(name);
|
||||
std::sort(gSortedWindows.begin(), gSortedWindows.end(),
|
||||
[](int a, int b) { return gWindows[a].name < gWindows[b].name; });
|
||||
}
|
||||
return &gWindows[index];
|
||||
}
|
||||
|
||||
static void SimWindowsReadLine(ImGuiContext* ctx, ImGuiSettingsHandler* handler,
|
||||
void* entry, const char* lineStr) {
|
||||
auto element = static_cast<WindowInfo*>(entry);
|
||||
wpi::StringRef line{lineStr};
|
||||
auto [name, value] = line.split('=');
|
||||
name = name.trim();
|
||||
value = value.trim();
|
||||
if (name == "visible") {
|
||||
int num;
|
||||
if (value.getAsInteger(10, num)) return;
|
||||
element->visible = num;
|
||||
} else if (name == "enabled") {
|
||||
int num;
|
||||
if (value.getAsInteger(10, num)) return;
|
||||
element->enabled = num;
|
||||
}
|
||||
}
|
||||
|
||||
static void SimWindowsWriteAll(ImGuiContext* ctx, ImGuiSettingsHandler* handler,
|
||||
ImGuiTextBuffer* out_buf) {
|
||||
for (auto&& window : gWindows)
|
||||
out_buf->appendf("[SimWindow][%s]\nvisible=%d\nenabled=%d\n\n",
|
||||
window.name.c_str(), window.visible ? 1 : 0,
|
||||
window.enabled ? 1 : 0);
|
||||
}
|
||||
|
||||
void HALSimGui::Add(std::function<void()> initialize) {
|
||||
if (initialize) gInitializers.emplace_back(std::move(initialize));
|
||||
}
|
||||
|
||||
void HALSimGui::AddExecute(std::function<void()> execute) {
|
||||
if (execute) gExecutors.emplace_back(std::move(execute));
|
||||
}
|
||||
|
||||
void HALSimGui::AddWindow(const char* name, std::function<void()> display,
|
||||
int flags) {
|
||||
if (display) {
|
||||
int index = gWindowMap.try_emplace(name, gWindows.size()).first->second;
|
||||
if (index < static_cast<int>(gWindows.size())) {
|
||||
if (gWindows[index].display) {
|
||||
wpi::errs() << "halsim_gui: ignoring duplicate window '" << name
|
||||
<< "'\n";
|
||||
} else {
|
||||
gWindows[index].display = display;
|
||||
gWindows[index].flags = flags;
|
||||
}
|
||||
return;
|
||||
}
|
||||
gSortedWindows.push_back(index);
|
||||
gWindows.emplace_back(name, std::move(display),
|
||||
static_cast<ImGuiWindowFlags>(flags));
|
||||
std::sort(gSortedWindows.begin(), gSortedWindows.end(),
|
||||
[](int a, int b) { return gWindows[a].name < gWindows[b].name; });
|
||||
}
|
||||
}
|
||||
|
||||
void HALSimGui::AddMainMenu(std::function<void()> menu) {
|
||||
if (menu) gMenus.emplace_back(std::move(menu));
|
||||
}
|
||||
|
||||
void HALSimGui::AddOptionMenu(std::function<void()> menu) {
|
||||
if (menu) gOptionMenus.emplace_back(std::move(menu));
|
||||
}
|
||||
|
||||
void HALSimGui::SetWindowVisibility(const char* name,
|
||||
WindowVisibility visibility) {
|
||||
auto it = gWindowMap.find(name);
|
||||
if (it == gWindowMap.end()) return;
|
||||
auto& window = gWindows[it->second];
|
||||
switch (visibility) {
|
||||
case kHide:
|
||||
window.visible = false;
|
||||
window.enabled = true;
|
||||
break;
|
||||
case kShow:
|
||||
window.visible = true;
|
||||
window.enabled = true;
|
||||
break;
|
||||
case kDisabled:
|
||||
window.enabled = false;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void HALSimGui::SetDefaultWindowPos(const char* name, float x, float y) {
|
||||
auto it = gWindowMap.find(name);
|
||||
if (it == gWindowMap.end()) return;
|
||||
auto& window = gWindows[it->second];
|
||||
window.posCond = ImGuiCond_FirstUseEver;
|
||||
window.pos = ImVec2{x, y};
|
||||
}
|
||||
|
||||
void HALSimGui::SetDefaultWindowSize(const char* name, float width,
|
||||
float height) {
|
||||
auto it = gWindowMap.find(name);
|
||||
if (it == gWindowMap.end()) return;
|
||||
auto& window = gWindows[it->second];
|
||||
window.sizeCond = ImGuiCond_FirstUseEver;
|
||||
window.size = ImVec2{width, height};
|
||||
}
|
||||
|
||||
bool HALSimGui::Initialize() {
|
||||
// Setup window
|
||||
glfwSetErrorCallback(glfw_error_callback);
|
||||
glfwInitHint(GLFW_JOYSTICK_HAT_BUTTONS, GLFW_FALSE);
|
||||
if (!glfwInit()) return false;
|
||||
|
||||
// Decide GL+GLSL versions
|
||||
#if __APPLE__
|
||||
// GL 3.2 + GLSL 150
|
||||
const char* glsl_version = "#version 150";
|
||||
glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 3);
|
||||
glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 2);
|
||||
glfwWindowHint(GLFW_OPENGL_PROFILE, GLFW_OPENGL_CORE_PROFILE); // 3.2+ only
|
||||
glfwWindowHint(GLFW_OPENGL_FORWARD_COMPAT, GL_TRUE); // Required on Mac
|
||||
#else
|
||||
// GL 3.0 + GLSL 130
|
||||
const char* glsl_version = "#version 130";
|
||||
glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 3);
|
||||
glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 0);
|
||||
// glfwWindowHint(GLFW_OPENGL_PROFILE, GLFW_OPENGL_CORE_PROFILE); // 3.2+
|
||||
// glfwWindowHint(GLFW_OPENGL_FORWARD_COMPAT, GL_TRUE); // 3.0+
|
||||
#endif
|
||||
|
||||
// Create window with graphics context
|
||||
gWindow =
|
||||
glfwCreateWindow(1280, 720, "Robot Simulation GUI", nullptr, nullptr);
|
||||
if (!gWindow) return false;
|
||||
glfwMakeContextCurrent(gWindow);
|
||||
glfwSwapInterval(1); // Enable vsync
|
||||
|
||||
// Initialize OpenGL loader
|
||||
if (gl3wInit() != 0) {
|
||||
wpi::errs() << "Failed to initialize OpenGL loader!\n";
|
||||
return false;
|
||||
}
|
||||
|
||||
// Setup Dear ImGui context
|
||||
IMGUI_CHECKVERSION();
|
||||
ImGui::CreateContext();
|
||||
ImGuiIO& io = ImGui::GetIO();
|
||||
(void)io;
|
||||
|
||||
// Setup Dear ImGui style
|
||||
// ImGui::StyleColorsDark();
|
||||
ImGui::StyleColorsClassic();
|
||||
|
||||
// Setup Platform/Renderer bindings
|
||||
ImGui_ImplGlfw_InitForOpenGL(gWindow, true);
|
||||
ImGui_ImplOpenGL3_Init(glsl_version);
|
||||
|
||||
// Load Fonts
|
||||
// - If no fonts are loaded, dear imgui will use the default font. You can
|
||||
// also load multiple fonts and use ImGui::PushFont()/PopFont() to select
|
||||
// them.
|
||||
// - AddFontFromFileTTF() will return the ImFont* so you can store it if you
|
||||
// need to select the font among multiple.
|
||||
// - If the file cannot be loaded, the function will return NULL. Please
|
||||
// handle those errors in your application (e.g. use an assertion, or display
|
||||
// an error and quit).
|
||||
// - The fonts will be rasterized at a given size (w/ oversampling) and stored
|
||||
// into a texture when calling ImFontAtlas::Build()/GetTexDataAsXXXX(), which
|
||||
// ImGui_ImplXXXX_NewFrame below will call.
|
||||
// - Read 'misc/fonts/README.txt' for more instructions and details.
|
||||
// - Remember that in C/C++ if you want to include a backslash \ in a string
|
||||
// literal you need to write a double backslash \\ !
|
||||
// io.Fonts->AddFontDefault();
|
||||
// io.Fonts->AddFontFromFileTTF("../../misc/fonts/Roboto-Medium.ttf", 16.0f);
|
||||
// io.Fonts->AddFontFromFileTTF("../../misc/fonts/Cousine-Regular.ttf", 15.0f);
|
||||
// io.Fonts->AddFontFromFileTTF("../../misc/fonts/DroidSans.ttf", 16.0f);
|
||||
// io.Fonts->AddFontFromFileTTF("../../misc/fonts/ProggyTiny.ttf", 10.0f);
|
||||
// ImFont* font =
|
||||
// io.Fonts->AddFontFromFileTTF("c:\\Windows\\Fonts\\ArialUni.ttf", 18.0f,
|
||||
// NULL, io.Fonts->GetGlyphRangesJapanese()); IM_ASSERT(font != NULL);
|
||||
|
||||
// hook ini handler to save settings
|
||||
ImGuiSettingsHandler iniHandler;
|
||||
iniHandler.TypeName = "SimWindow";
|
||||
iniHandler.TypeHash = ImHashStr(iniHandler.TypeName);
|
||||
iniHandler.ReadOpenFn = SimWindowsReadOpen;
|
||||
iniHandler.ReadLineFn = SimWindowsReadLine;
|
||||
iniHandler.WriteAllFn = SimWindowsWriteAll;
|
||||
ImGui::GetCurrentContext()->SettingsHandlers.push_back(iniHandler);
|
||||
|
||||
for (auto&& initialize : gInitializers) {
|
||||
if (initialize) initialize();
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void HALSimGui::Main(void*) {
|
||||
ImVec4 clear_color = ImVec4(0.45f, 0.55f, 0.60f, 1.00f);
|
||||
|
||||
// Main loop
|
||||
while (!glfwWindowShouldClose(gWindow) && !gExit) {
|
||||
// Poll and handle events (inputs, window resize, etc.)
|
||||
glfwPollEvents();
|
||||
|
||||
// Start the Dear ImGui frame
|
||||
ImGui_ImplOpenGL3_NewFrame();
|
||||
ImGui_ImplGlfw_NewFrame();
|
||||
ImGui::NewFrame();
|
||||
|
||||
for (auto&& execute : gExecutors) {
|
||||
if (execute) execute();
|
||||
}
|
||||
|
||||
{
|
||||
ImGui::BeginMainMenuBar();
|
||||
|
||||
if (ImGui::BeginMenu("Options")) {
|
||||
for (auto&& menu : gOptionMenus) {
|
||||
if (menu) menu();
|
||||
}
|
||||
ImGui::EndMenu();
|
||||
}
|
||||
|
||||
if (ImGui::BeginMenu("Window")) {
|
||||
for (auto&& windowIndex : gSortedWindows) {
|
||||
auto& window = gWindows[windowIndex];
|
||||
ImGui::MenuItem(window.name.c_str(), nullptr, &window.visible,
|
||||
window.enabled);
|
||||
}
|
||||
ImGui::EndMenu();
|
||||
}
|
||||
|
||||
for (auto&& menu : gMenus) {
|
||||
if (menu) menu();
|
||||
}
|
||||
|
||||
#if 0
|
||||
char str[64];
|
||||
std::snprintf(str, sizeof(str), "%.3f ms/frame (%.1f FPS)",
|
||||
1000.0f / ImGui::GetIO().Framerate,
|
||||
ImGui::GetIO().Framerate);
|
||||
ImGui::SameLine(ImGui::GetWindowWidth() - ImGui::CalcTextSize(str).x -
|
||||
10);
|
||||
ImGui::Text("%s", str);
|
||||
#endif
|
||||
ImGui::EndMainMenuBar();
|
||||
}
|
||||
|
||||
for (auto&& window : gWindows) {
|
||||
if (window.display && window.visible && window.enabled) {
|
||||
if (window.posCond != 0)
|
||||
ImGui::SetNextWindowPos(window.pos, window.posCond);
|
||||
if (window.sizeCond != 0)
|
||||
ImGui::SetNextWindowSize(window.size, window.sizeCond);
|
||||
if (ImGui::Begin(window.name.c_str(), &window.visible, window.flags))
|
||||
window.display();
|
||||
ImGui::End();
|
||||
}
|
||||
}
|
||||
|
||||
// Rendering
|
||||
ImGui::Render();
|
||||
int display_w, display_h;
|
||||
glfwGetFramebufferSize(gWindow, &display_w, &display_h);
|
||||
glViewport(0, 0, display_w, display_h);
|
||||
glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w);
|
||||
glClear(GL_COLOR_BUFFER_BIT);
|
||||
ImGui_ImplOpenGL3_RenderDrawData(ImGui::GetDrawData());
|
||||
|
||||
glfwSwapBuffers(gWindow);
|
||||
}
|
||||
|
||||
// Cleanup
|
||||
ImGui_ImplOpenGL3_Shutdown();
|
||||
ImGui_ImplGlfw_Shutdown();
|
||||
ImGui::DestroyContext();
|
||||
|
||||
glfwDestroyWindow(gWindow);
|
||||
glfwTerminate();
|
||||
}
|
||||
|
||||
void HALSimGui::Exit(void*) { gExit = true; }
|
||||
|
||||
extern "C" {
|
||||
|
||||
void HALSIMGUI_Add(void* param, void (*initialize)(void*)) {
|
||||
if (initialize) {
|
||||
HALSimGui::Add([=] { initialize(param); });
|
||||
}
|
||||
}
|
||||
|
||||
void HALSIMGUI_AddExecute(void* param, void (*execute)(void*)) {
|
||||
if (execute) {
|
||||
HALSimGui::AddExecute([=] { execute(param); });
|
||||
}
|
||||
}
|
||||
|
||||
void HALSIMGUI_AddWindow(const char* name, void* param, void (*display)(void*),
|
||||
int32_t flags) {
|
||||
if (display) {
|
||||
HALSimGui::AddWindow(name, [=] { display(param); }, flags);
|
||||
}
|
||||
}
|
||||
|
||||
void HALSIMGUI_AddMainMenu(void* param, void (*menu)(void*)) {
|
||||
if (menu) {
|
||||
HALSimGui::AddMainMenu([=] { menu(param); });
|
||||
}
|
||||
}
|
||||
|
||||
void HALSIMGUI_AddOptionMenu(void* param, void (*menu)(void*)) {
|
||||
if (menu) {
|
||||
HALSimGui::AddOptionMenu([=] { menu(param); });
|
||||
}
|
||||
}
|
||||
|
||||
void HALSIMGUI_SetWindowVisibility(const char* name, int32_t visibility) {
|
||||
HALSimGui::SetWindowVisibility(
|
||||
name, static_cast<HALSimGui::WindowVisibility>(visibility));
|
||||
}
|
||||
|
||||
void HALSIMGUI_SetDefaultWindowPos(const char* name, float x, float y) {
|
||||
HALSimGui::SetDefaultWindowPos(name, x, y);
|
||||
}
|
||||
|
||||
void HALSIMGUI_SetDefaultWindowSize(const char* name, float width,
|
||||
float height) {
|
||||
HALSimGui::SetDefaultWindowSize(name, width, height);
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
77
simulation/halsim_gui/src/main/native/cpp/PDPGui.cpp
Normal file
77
simulation/halsim_gui/src/main/native/cpp/PDPGui.cpp
Normal file
@@ -0,0 +1,77 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "PDPGui.h"
|
||||
|
||||
#include <cstdio>
|
||||
|
||||
#include <hal/Ports.h>
|
||||
#include <imgui.h>
|
||||
#include <mockdata/PDPData.h>
|
||||
|
||||
#include "HALSimGui.h"
|
||||
|
||||
using namespace halsimgui;
|
||||
|
||||
static void DisplayPDP() {
|
||||
bool hasAny = false;
|
||||
static int numPDP = HAL_GetNumPDPModules();
|
||||
static int numChannels = HAL_GetNumPDPChannels();
|
||||
ImGui::PushItemWidth(150);
|
||||
for (int i = 0; i < numPDP; ++i) {
|
||||
if (HALSIM_GetPDPInitialized(i)) {
|
||||
hasAny = true;
|
||||
|
||||
char name[32];
|
||||
std::snprintf(name, sizeof(name), "PDP[%d]", i);
|
||||
if (ImGui::CollapsingHeader(name, ImGuiTreeNodeFlags_DefaultOpen)) {
|
||||
ImGui::PushID(i);
|
||||
|
||||
// temperature
|
||||
double temp = HALSIM_GetPDPTemperature(i);
|
||||
if (ImGui::InputDouble("Temp", &temp))
|
||||
HALSIM_SetPDPTemperature(i, temp);
|
||||
|
||||
// voltage
|
||||
double volts = HALSIM_GetPDPVoltage(i);
|
||||
if (ImGui::InputDouble("Voltage", &volts))
|
||||
HALSIM_SetPDPVoltage(i, volts);
|
||||
|
||||
// channel currents; show as two columns laid out like PDP
|
||||
ImGui::Text("Channel Current (A)");
|
||||
ImGui::Columns(2, "channels", false);
|
||||
for (int left = 0, right = numChannels - 1; left < right;
|
||||
++left, --right) {
|
||||
double val;
|
||||
|
||||
std::snprintf(name, sizeof(name), "[%d]", left);
|
||||
val = HALSIM_GetPDPCurrent(i, left);
|
||||
if (ImGui::InputDouble(name, &val))
|
||||
HALSIM_SetPDPCurrent(i, left, val);
|
||||
ImGui::NextColumn();
|
||||
|
||||
std::snprintf(name, sizeof(name), "[%d]", right);
|
||||
val = HALSIM_GetPDPCurrent(i, right);
|
||||
if (ImGui::InputDouble(name, &val))
|
||||
HALSIM_SetPDPCurrent(i, right, val);
|
||||
ImGui::NextColumn();
|
||||
}
|
||||
ImGui::Columns(1);
|
||||
ImGui::PopID();
|
||||
}
|
||||
}
|
||||
}
|
||||
ImGui::PopItemWidth();
|
||||
if (!hasAny) ImGui::Text("No PDPs");
|
||||
}
|
||||
|
||||
void PDPGui::Initialize() {
|
||||
HALSimGui::AddWindow("PDP", DisplayPDP, ImGuiWindowFlags_AlwaysAutoResize);
|
||||
// hide it by default
|
||||
HALSimGui::SetWindowVisibility("PDP", HALSimGui::kHide);
|
||||
HALSimGui::SetDefaultWindowPos("PDP", 245, 155);
|
||||
}
|
||||
17
simulation/halsim_gui/src/main/native/cpp/PDPGui.h
Normal file
17
simulation/halsim_gui/src/main/native/cpp/PDPGui.h
Normal file
@@ -0,0 +1,17 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
namespace halsimgui {
|
||||
|
||||
class PDPGui {
|
||||
public:
|
||||
static void Initialize();
|
||||
};
|
||||
|
||||
} // namespace halsimgui
|
||||
66
simulation/halsim_gui/src/main/native/cpp/PWMGui.cpp
Normal file
66
simulation/halsim_gui/src/main/native/cpp/PWMGui.cpp
Normal file
@@ -0,0 +1,66 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "PWMGui.h"
|
||||
|
||||
#include <cstdio>
|
||||
#include <cstring>
|
||||
|
||||
#include <hal/Ports.h>
|
||||
#include <imgui.h>
|
||||
#include <mockdata/PWMData.h>
|
||||
|
||||
#include "HALSimGui.h"
|
||||
|
||||
using namespace halsimgui;
|
||||
|
||||
static void DisplayPWMs() {
|
||||
bool hasOutputs = false;
|
||||
// struct History {
|
||||
// History() { std::memset(data, 0, 90 * sizeof(float)); }
|
||||
// History(const History&) = delete;
|
||||
// History& operator=(const History&) = delete;
|
||||
// float data[90];
|
||||
// int display_offset = 0;
|
||||
// int save_offset = 0;
|
||||
//};
|
||||
// static std::vector<std::unique_ptr<History>> history;
|
||||
bool first = true;
|
||||
static const int numPWM = HAL_GetNumPWMChannels();
|
||||
for (int i = 0; i < numPWM; ++i) {
|
||||
if (HALSIM_GetPWMInitialized(i)) {
|
||||
hasOutputs = true;
|
||||
|
||||
if (!first)
|
||||
ImGui::Separator();
|
||||
else
|
||||
first = false;
|
||||
|
||||
char name[32];
|
||||
std::snprintf(name, sizeof(name), "PWM[%d]", i);
|
||||
float val = HALSIM_GetPWMSpeed(i);
|
||||
ImGui::Value(name, val, "%0.3f");
|
||||
|
||||
// lazily build history storage
|
||||
// if (static_cast<unsigned int>(i) > history.size())
|
||||
// history.resize(i + 1);
|
||||
// if (!history[i]) history[i] = std::make_unique<History>();
|
||||
|
||||
// save history
|
||||
|
||||
// ImGui::PlotLines(labels[i].c_str(), values.data(), values.size(),
|
||||
// );
|
||||
}
|
||||
}
|
||||
if (!hasOutputs) ImGui::Text("No PWM outputs");
|
||||
}
|
||||
|
||||
void PWMGui::Initialize() {
|
||||
HALSimGui::AddWindow("PWM Outputs", DisplayPWMs,
|
||||
ImGuiWindowFlags_AlwaysAutoResize);
|
||||
HALSimGui::SetDefaultWindowPos("PWM Outputs", 910, 20);
|
||||
}
|
||||
17
simulation/halsim_gui/src/main/native/cpp/PWMGui.h
Normal file
17
simulation/halsim_gui/src/main/native/cpp/PWMGui.h
Normal file
@@ -0,0 +1,17 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
namespace halsimgui {
|
||||
|
||||
class PWMGui {
|
||||
public:
|
||||
static void Initialize();
|
||||
};
|
||||
|
||||
} // namespace halsimgui
|
||||
60
simulation/halsim_gui/src/main/native/cpp/RelayGui.cpp
Normal file
60
simulation/halsim_gui/src/main/native/cpp/RelayGui.cpp
Normal file
@@ -0,0 +1,60 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "RelayGui.h"
|
||||
|
||||
#include <cstdio>
|
||||
#include <cstring>
|
||||
|
||||
#include <hal/Ports.h>
|
||||
#include <imgui.h>
|
||||
#include <mockdata/RelayData.h>
|
||||
|
||||
#include "ExtraGuiWidgets.h"
|
||||
#include "HALSimGui.h"
|
||||
|
||||
using namespace halsimgui;
|
||||
|
||||
static void DisplayRelays() {
|
||||
bool hasOutputs = false;
|
||||
bool first = true;
|
||||
static const int numRelay = HAL_GetNumRelayHeaders();
|
||||
for (int i = 0; i < numRelay; ++i) {
|
||||
bool forwardInit = HALSIM_GetRelayInitializedForward(i);
|
||||
bool reverseInit = HALSIM_GetRelayInitializedReverse(i);
|
||||
|
||||
if (forwardInit || reverseInit) {
|
||||
hasOutputs = true;
|
||||
|
||||
if (!first)
|
||||
ImGui::Separator();
|
||||
else
|
||||
first = false;
|
||||
|
||||
bool forward = HALSIM_GetRelayForward(i);
|
||||
bool reverse = HALSIM_GetRelayReverse(i);
|
||||
|
||||
ImGui::Text("Relay[%d]", i);
|
||||
ImGui::SameLine();
|
||||
|
||||
// show forward and reverse as LED indicators
|
||||
static const ImU32 colors[] = {IM_COL32(255, 255, 102, 255),
|
||||
IM_COL32(255, 0, 0, 255),
|
||||
IM_COL32(128, 128, 128, 255)};
|
||||
int values[2] = {reverseInit ? (reverse ? 2 : -2) : -3,
|
||||
forwardInit ? (forward ? 1 : -1) : -3};
|
||||
DrawLEDs(values, 2, 2, colors);
|
||||
}
|
||||
}
|
||||
if (!hasOutputs) ImGui::Text("No relays");
|
||||
}
|
||||
|
||||
void RelayGui::Initialize() {
|
||||
HALSimGui::AddWindow("Relays", DisplayRelays,
|
||||
ImGuiWindowFlags_AlwaysAutoResize);
|
||||
HALSimGui::SetDefaultWindowPos("Relays", 180, 20);
|
||||
}
|
||||
17
simulation/halsim_gui/src/main/native/cpp/RelayGui.h
Normal file
17
simulation/halsim_gui/src/main/native/cpp/RelayGui.h
Normal file
@@ -0,0 +1,17 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
namespace halsimgui {
|
||||
|
||||
class RelayGui {
|
||||
public:
|
||||
static void Initialize();
|
||||
};
|
||||
|
||||
} // namespace halsimgui
|
||||
127
simulation/halsim_gui/src/main/native/cpp/RoboRioGui.cpp
Normal file
127
simulation/halsim_gui/src/main/native/cpp/RoboRioGui.cpp
Normal file
@@ -0,0 +1,127 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "RoboRioGui.h"
|
||||
|
||||
#include <imgui.h>
|
||||
#include <mockdata/RoboRioData.h>
|
||||
|
||||
#include "HALSimGui.h"
|
||||
|
||||
using namespace halsimgui;
|
||||
|
||||
static void DisplayRoboRio() {
|
||||
ImGui::Button("User Button");
|
||||
HALSIM_SetRoboRioFPGAButton(0, ImGui::IsItemActive());
|
||||
|
||||
ImGui::PushItemWidth(100);
|
||||
|
||||
if (ImGui::CollapsingHeader("RoboRIO Input")) {
|
||||
{
|
||||
double val = HALSIM_GetRoboRioVInVoltage(0);
|
||||
if (ImGui::InputDouble("Voltage (V)", &val))
|
||||
HALSIM_SetRoboRioVInVoltage(0, val);
|
||||
}
|
||||
|
||||
{
|
||||
double val = HALSIM_GetRoboRioVInCurrent(0);
|
||||
if (ImGui::InputDouble("Current (A)", &val))
|
||||
HALSIM_SetRoboRioVInCurrent(0, val);
|
||||
}
|
||||
}
|
||||
|
||||
if (ImGui::CollapsingHeader("6V Rail")) {
|
||||
{
|
||||
double val = HALSIM_GetRoboRioUserVoltage6V(0);
|
||||
if (ImGui::InputDouble("Voltage (V)", &val))
|
||||
HALSIM_SetRoboRioUserVoltage6V(0, val);
|
||||
}
|
||||
|
||||
{
|
||||
double val = HALSIM_GetRoboRioUserCurrent6V(0);
|
||||
if (ImGui::InputDouble("Current (A)", &val))
|
||||
HALSIM_SetRoboRioUserCurrent6V(0, val);
|
||||
}
|
||||
|
||||
{
|
||||
static const char* options[] = {"inactive", "active"};
|
||||
int val = HALSIM_GetRoboRioUserActive6V(0) ? 1 : 0;
|
||||
if (ImGui::Combo("Active", &val, options, 2))
|
||||
HALSIM_SetRoboRioUserActive6V(0, val);
|
||||
}
|
||||
|
||||
{
|
||||
int val = HALSIM_GetRoboRioUserFaults6V(0);
|
||||
if (ImGui::InputInt("Faults", &val))
|
||||
HALSIM_SetRoboRioUserFaults6V(0, val);
|
||||
}
|
||||
}
|
||||
|
||||
if (ImGui::CollapsingHeader("5V Rail")) {
|
||||
{
|
||||
double val = HALSIM_GetRoboRioUserVoltage5V(0);
|
||||
if (ImGui::InputDouble("Voltage (V)", &val))
|
||||
HALSIM_SetRoboRioUserVoltage5V(0, val);
|
||||
}
|
||||
|
||||
{
|
||||
double val = HALSIM_GetRoboRioUserCurrent5V(0);
|
||||
if (ImGui::InputDouble("Current (A)", &val))
|
||||
HALSIM_SetRoboRioUserCurrent5V(0, val);
|
||||
}
|
||||
|
||||
{
|
||||
static const char* options[] = {"inactive", "active"};
|
||||
int val = HALSIM_GetRoboRioUserActive5V(0) ? 1 : 0;
|
||||
if (ImGui::Combo("Active", &val, options, 2))
|
||||
HALSIM_SetRoboRioUserActive5V(0, val);
|
||||
}
|
||||
|
||||
{
|
||||
int val = HALSIM_GetRoboRioUserFaults5V(0);
|
||||
if (ImGui::InputInt("Faults", &val))
|
||||
HALSIM_SetRoboRioUserFaults5V(0, val);
|
||||
}
|
||||
}
|
||||
|
||||
if (ImGui::CollapsingHeader("3.3V Rail")) {
|
||||
{
|
||||
double val = HALSIM_GetRoboRioUserVoltage3V3(0);
|
||||
if (ImGui::InputDouble("Voltage (V)", &val))
|
||||
HALSIM_SetRoboRioUserVoltage3V3(0, val);
|
||||
}
|
||||
|
||||
{
|
||||
double val = HALSIM_GetRoboRioUserCurrent3V3(0);
|
||||
if (ImGui::InputDouble("Current (A)", &val))
|
||||
HALSIM_SetRoboRioUserCurrent3V3(0, val);
|
||||
}
|
||||
|
||||
{
|
||||
static const char* options[] = {"inactive", "active"};
|
||||
int val = HALSIM_GetRoboRioUserActive3V3(0) ? 1 : 0;
|
||||
if (ImGui::Combo("Active", &val, options, 2))
|
||||
HALSIM_SetRoboRioUserActive3V3(0, val);
|
||||
}
|
||||
|
||||
{
|
||||
int val = HALSIM_GetRoboRioUserFaults3V3(0);
|
||||
if (ImGui::InputInt("Faults", &val))
|
||||
HALSIM_SetRoboRioUserFaults3V3(0, val);
|
||||
}
|
||||
}
|
||||
|
||||
ImGui::PopItemWidth();
|
||||
}
|
||||
|
||||
void RoboRioGui::Initialize() {
|
||||
HALSimGui::AddWindow("RoboRIO", DisplayRoboRio,
|
||||
ImGuiWindowFlags_AlwaysAutoResize);
|
||||
// hide it by default
|
||||
HALSimGui::SetWindowVisibility("RoboRIO", HALSimGui::kHide);
|
||||
HALSimGui::SetDefaultWindowPos("RoboRIO", 5, 125);
|
||||
}
|
||||
17
simulation/halsim_gui/src/main/native/cpp/RoboRioGui.h
Normal file
17
simulation/halsim_gui/src/main/native/cpp/RoboRioGui.h
Normal file
@@ -0,0 +1,17 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
namespace halsimgui {
|
||||
|
||||
class RoboRioGui {
|
||||
public:
|
||||
static void Initialize();
|
||||
};
|
||||
|
||||
} // namespace halsimgui
|
||||
239
simulation/halsim_gui/src/main/native/cpp/SimDeviceGui.cpp
Normal file
239
simulation/halsim_gui/src/main/native/cpp/SimDeviceGui.cpp
Normal file
@@ -0,0 +1,239 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "SimDeviceGui.h"
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <vector>
|
||||
|
||||
#include <hal/SimDevice.h>
|
||||
#include <imgui.h>
|
||||
#include <imgui_internal.h>
|
||||
#include <mockdata/SimDeviceData.h>
|
||||
#include <wpi/StringMap.h>
|
||||
|
||||
#include "HALSimGui.h"
|
||||
|
||||
using namespace halsimgui;
|
||||
|
||||
namespace {
|
||||
struct ElementInfo {
|
||||
bool open = false;
|
||||
bool visible = true;
|
||||
};
|
||||
} // namespace
|
||||
|
||||
static std::vector<std::function<void()>> gDeviceExecutors;
|
||||
static wpi::StringMap<ElementInfo> gElements;
|
||||
|
||||
// read/write open state to ini file
|
||||
static void* DevicesReadOpen(ImGuiContext* ctx, ImGuiSettingsHandler* handler,
|
||||
const char* name) {
|
||||
return &gElements[name];
|
||||
}
|
||||
|
||||
static void DevicesReadLine(ImGuiContext* ctx, ImGuiSettingsHandler* handler,
|
||||
void* entry, const char* lineStr) {
|
||||
ElementInfo* element = static_cast<ElementInfo*>(entry);
|
||||
wpi::StringRef line{lineStr};
|
||||
auto [name, value] = line.split('=');
|
||||
name = name.trim();
|
||||
value = value.trim();
|
||||
if (name == "open") {
|
||||
int num;
|
||||
if (value.getAsInteger(10, num)) return;
|
||||
element->open = num;
|
||||
}
|
||||
}
|
||||
|
||||
static void DevicesWriteAll(ImGuiContext* ctx, ImGuiSettingsHandler* handler,
|
||||
ImGuiTextBuffer* out_buf) {
|
||||
for (auto&& entry : gElements) {
|
||||
out_buf->appendf("[Device][%s]\nopen=%d\n\n", entry.getKey().data(),
|
||||
entry.getValue().open ? 1 : 0);
|
||||
}
|
||||
}
|
||||
|
||||
void SimDeviceGui::Hide(const char* name) { gElements[name].visible = false; }
|
||||
|
||||
void SimDeviceGui::Add(std::function<void()> execute) {
|
||||
if (execute) gDeviceExecutors.emplace_back(std::move(execute));
|
||||
}
|
||||
|
||||
bool SimDeviceGui::StartDevice(const char* label, ImGuiTreeNodeFlags flags) {
|
||||
auto& element = gElements[label];
|
||||
if (!element.visible) return false;
|
||||
|
||||
if (ImGui::CollapsingHeader(
|
||||
label, flags | (element.open ? ImGuiTreeNodeFlags_DefaultOpen : 0))) {
|
||||
ImGui::PushID(label);
|
||||
element.open = true;
|
||||
return true;
|
||||
}
|
||||
element.open = false;
|
||||
return false;
|
||||
}
|
||||
|
||||
void SimDeviceGui::FinishDevice() { ImGui::PopID(); }
|
||||
|
||||
bool DisplayValueImpl(const char* name, bool readonly, HAL_Value* value,
|
||||
const char** options, int32_t numOptions) {
|
||||
// read-only
|
||||
if (readonly) {
|
||||
switch (value->type) {
|
||||
case HAL_BOOLEAN:
|
||||
ImGui::LabelText(name, "%s", value->data.v_boolean ? "true" : "false");
|
||||
break;
|
||||
case HAL_DOUBLE:
|
||||
ImGui::LabelText(name, "%.6f", value->data.v_double);
|
||||
break;
|
||||
case HAL_ENUM: {
|
||||
int current = value->data.v_enum;
|
||||
if (current < 0 || current >= numOptions)
|
||||
ImGui::LabelText(name, "%d (unknown)", current);
|
||||
else
|
||||
ImGui::LabelText(name, "%s", options[current]);
|
||||
break;
|
||||
}
|
||||
case HAL_INT:
|
||||
ImGui::LabelText(name, "%d", static_cast<int>(value->data.v_int));
|
||||
break;
|
||||
case HAL_LONG:
|
||||
ImGui::LabelText(name, "%lld",
|
||||
static_cast<long long int>( // NOLINT(runtime/int)
|
||||
value->data.v_long));
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
// writable
|
||||
switch (value->type) {
|
||||
case HAL_BOOLEAN: {
|
||||
static const char* boolOptions[] = {"false", "true"};
|
||||
int val = value->data.v_boolean ? 1 : 0;
|
||||
if (ImGui::Combo(name, &val, boolOptions, 2)) {
|
||||
value->data.v_boolean = val;
|
||||
return true;
|
||||
}
|
||||
break;
|
||||
}
|
||||
case HAL_DOUBLE: {
|
||||
if (ImGui::InputDouble(name, &value->data.v_double, 0, 0, "%.6f",
|
||||
ImGuiInputTextFlags_EnterReturnsTrue))
|
||||
return true;
|
||||
break;
|
||||
}
|
||||
case HAL_ENUM: {
|
||||
int current = value->data.v_enum;
|
||||
if (ImGui::Combo(name, ¤t, options, numOptions)) {
|
||||
value->data.v_enum = current;
|
||||
return true;
|
||||
}
|
||||
break;
|
||||
}
|
||||
case HAL_INT: {
|
||||
if (ImGui::InputScalar(name, ImGuiDataType_S32, &value->data.v_int,
|
||||
nullptr, nullptr, nullptr,
|
||||
ImGuiInputTextFlags_EnterReturnsTrue))
|
||||
return true;
|
||||
break;
|
||||
}
|
||||
case HAL_LONG: {
|
||||
if (ImGui::InputScalar(name, ImGuiDataType_S64, &value->data.v_long,
|
||||
nullptr, nullptr, nullptr,
|
||||
ImGuiInputTextFlags_EnterReturnsTrue))
|
||||
return true;
|
||||
break;
|
||||
}
|
||||
default:
|
||||
break;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool SimDeviceGui::DisplayValue(const char* name, bool readonly,
|
||||
HAL_Value* value, const char** options,
|
||||
int32_t numOptions) {
|
||||
ImGui::SetNextItemWidth(ImGui::GetWindowWidth() * 0.5f);
|
||||
return DisplayValueImpl(name, readonly, value, options, numOptions);
|
||||
}
|
||||
|
||||
static void SimDeviceDisplayValue(const char* name, void*,
|
||||
HAL_SimValueHandle handle, HAL_Bool readonly,
|
||||
const HAL_Value* value) {
|
||||
int32_t numOptions = 0;
|
||||
const char** options = nullptr;
|
||||
|
||||
if (value->type == HAL_ENUM)
|
||||
options = HALSIM_GetSimValueEnumOptions(handle, &numOptions);
|
||||
|
||||
HAL_Value valueCopy = *value;
|
||||
if (DisplayValueImpl(name, readonly, &valueCopy, options, numOptions))
|
||||
HAL_SetSimValue(handle, valueCopy);
|
||||
}
|
||||
|
||||
static void SimDeviceDisplayDevice(const char* name, void*,
|
||||
HAL_SimDeviceHandle handle) {
|
||||
auto it = gElements.find(name);
|
||||
if (it != gElements.end() && !it->second.visible) return;
|
||||
|
||||
if (SimDeviceGui::StartDevice(name)) {
|
||||
ImGui::PushItemWidth(ImGui::GetWindowWidth() * 0.5f);
|
||||
HALSIM_EnumerateSimValues(handle, nullptr, SimDeviceDisplayValue);
|
||||
ImGui::PopItemWidth();
|
||||
SimDeviceGui::FinishDevice();
|
||||
}
|
||||
}
|
||||
|
||||
static void DisplayDeviceTree() {
|
||||
for (auto&& execute : gDeviceExecutors) {
|
||||
if (execute) execute();
|
||||
}
|
||||
HALSIM_EnumerateSimDevices("", nullptr, SimDeviceDisplayDevice);
|
||||
}
|
||||
|
||||
void SimDeviceGui::Initialize() {
|
||||
// hook ini handler to save device settings
|
||||
ImGuiSettingsHandler iniHandler;
|
||||
iniHandler.TypeName = "Device";
|
||||
iniHandler.TypeHash = ImHashStr(iniHandler.TypeName);
|
||||
iniHandler.ReadOpenFn = DevicesReadOpen;
|
||||
iniHandler.ReadLineFn = DevicesReadLine;
|
||||
iniHandler.WriteAllFn = DevicesWriteAll;
|
||||
ImGui::GetCurrentContext()->SettingsHandlers.push_back(iniHandler);
|
||||
|
||||
HALSimGui::AddWindow("Other Devices", DisplayDeviceTree);
|
||||
HALSimGui::SetDefaultWindowPos("Other Devices", 1025, 20);
|
||||
HALSimGui::SetDefaultWindowSize("Other Devices", 250, 695);
|
||||
}
|
||||
|
||||
extern "C" {
|
||||
|
||||
void HALSIMGUI_DeviceTreeAdd(void* param, void (*execute)(void*)) {
|
||||
if (execute) SimDeviceGui::Add([=] { execute(param); });
|
||||
}
|
||||
|
||||
void HALSIMGUI_DeviceTreeHide(const char* name) { SimDeviceGui::Hide(name); }
|
||||
|
||||
HAL_Bool HALSIMGUI_DeviceTreeDisplayValue(const char* name, HAL_Bool readonly,
|
||||
struct HAL_Value* value,
|
||||
const char** options,
|
||||
int32_t numOptions) {
|
||||
return SimDeviceGui::DisplayValue(name, readonly, value, options, numOptions);
|
||||
}
|
||||
|
||||
HAL_Bool HALSIMGUI_DeviceTreeStartDevice(const char* label, int32_t flags) {
|
||||
return SimDeviceGui::StartDevice(label, flags);
|
||||
}
|
||||
|
||||
void HALSIMGUI_DeviceTreeFinishDevice(void) { SimDeviceGui::FinishDevice(); }
|
||||
|
||||
} // extern "C"
|
||||
58
simulation/halsim_gui/src/main/native/cpp/SolenoidGui.cpp
Normal file
58
simulation/halsim_gui/src/main/native/cpp/SolenoidGui.cpp
Normal file
@@ -0,0 +1,58 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "SolenoidGui.h"
|
||||
|
||||
#include <cstdio>
|
||||
#include <cstring>
|
||||
|
||||
#include <hal/Ports.h>
|
||||
#include <imgui.h>
|
||||
#include <mockdata/PCMData.h>
|
||||
#include <wpi/SmallVector.h>
|
||||
|
||||
#include "ExtraGuiWidgets.h"
|
||||
#include "HALSimGui.h"
|
||||
|
||||
using namespace halsimgui;
|
||||
|
||||
static void DisplaySolenoids() {
|
||||
bool hasOutputs = false;
|
||||
static const int numPCM = HAL_GetNumPCMModules();
|
||||
static const int numChannels = HAL_GetNumSolenoidChannels();
|
||||
for (int i = 0; i < numPCM; ++i) {
|
||||
bool anyInit = false;
|
||||
wpi::SmallVector<int, 16> channels;
|
||||
channels.resize(numChannels);
|
||||
for (int j = 0; j < numChannels; ++j) {
|
||||
if (HALSIM_GetPCMSolenoidInitialized(i, j)) {
|
||||
anyInit = true;
|
||||
channels[j] = HALSIM_GetPCMSolenoidOutput(i, j) ? 1 : -1;
|
||||
} else {
|
||||
channels[j] = -2;
|
||||
}
|
||||
}
|
||||
|
||||
if (!anyInit) continue;
|
||||
hasOutputs = true;
|
||||
|
||||
ImGui::Text("PCM[%d]", i);
|
||||
ImGui::SameLine();
|
||||
|
||||
// show channels as LED indicators
|
||||
static const ImU32 colors[] = {IM_COL32(255, 255, 102, 255),
|
||||
IM_COL32(128, 128, 128, 255)};
|
||||
DrawLEDs(channels.data(), channels.size(), channels.size(), colors);
|
||||
}
|
||||
if (!hasOutputs) ImGui::Text("No solenoids");
|
||||
}
|
||||
|
||||
void SolenoidGui::Initialize() {
|
||||
HALSimGui::AddWindow("Solenoids", DisplaySolenoids,
|
||||
ImGuiWindowFlags_AlwaysAutoResize);
|
||||
HALSimGui::SetDefaultWindowPos("Solenoids", 290, 20);
|
||||
}
|
||||
17
simulation/halsim_gui/src/main/native/cpp/SolenoidGui.h
Normal file
17
simulation/halsim_gui/src/main/native/cpp/SolenoidGui.h
Normal file
@@ -0,0 +1,17 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
namespace halsimgui {
|
||||
|
||||
class SolenoidGui {
|
||||
public:
|
||||
static void Initialize();
|
||||
};
|
||||
|
||||
} // namespace halsimgui
|
||||
56
simulation/halsim_gui/src/main/native/cpp/main.cpp
Normal file
56
simulation/halsim_gui/src/main/native/cpp/main.cpp
Normal file
@@ -0,0 +1,56 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <hal/Main.h>
|
||||
#include <wpi/raw_ostream.h>
|
||||
|
||||
#include "AccelerometerGui.h"
|
||||
#include "AnalogGyroGui.h"
|
||||
#include "AnalogInputGui.h"
|
||||
#include "AnalogOutGui.h"
|
||||
#include "CompressorGui.h"
|
||||
#include "DIOGui.h"
|
||||
#include "DriverStationGui.h"
|
||||
#include "EncoderGui.h"
|
||||
#include "HALSimGui.h"
|
||||
#include "PDPGui.h"
|
||||
#include "PWMGui.h"
|
||||
#include "RelayGui.h"
|
||||
#include "RoboRioGui.h"
|
||||
#include "SimDeviceGui.h"
|
||||
#include "SolenoidGui.h"
|
||||
|
||||
using namespace halsimgui;
|
||||
|
||||
extern "C" {
|
||||
#if defined(WIN32) || defined(_WIN32)
|
||||
__declspec(dllexport)
|
||||
#endif
|
||||
int HALSIM_InitExtension(void) {
|
||||
HALSimGui::Add(AccelerometerGui::Initialize);
|
||||
HALSimGui::Add(AnalogGyroGui::Initialize);
|
||||
HALSimGui::Add(AnalogInputGui::Initialize);
|
||||
HALSimGui::Add(AnalogOutGui::Initialize);
|
||||
HALSimGui::Add(CompressorGui::Initialize);
|
||||
HALSimGui::Add(DriverStationGui::Initialize);
|
||||
HALSimGui::Add(DIOGui::Initialize);
|
||||
HALSimGui::Add(EncoderGui::Initialize);
|
||||
HALSimGui::Add(PDPGui::Initialize);
|
||||
HALSimGui::Add(PWMGui::Initialize);
|
||||
HALSimGui::Add(RelayGui::Initialize);
|
||||
HALSimGui::Add(RoboRioGui::Initialize);
|
||||
HALSimGui::Add(SimDeviceGui::Initialize);
|
||||
HALSimGui::Add(SolenoidGui::Initialize);
|
||||
|
||||
wpi::outs() << "Simulator GUI Initializing.\n";
|
||||
if (!HALSimGui::Initialize()) return 0;
|
||||
HAL_SetMain(nullptr, HALSimGui::Main, HALSimGui::Exit);
|
||||
wpi::outs() << "Simulator GUI Initialized!\n";
|
||||
|
||||
return 0;
|
||||
}
|
||||
} // extern "C"
|
||||
@@ -0,0 +1,32 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <imgui.h>
|
||||
|
||||
namespace halsimgui {
|
||||
|
||||
/**
|
||||
* Draw a 2D array of LEDs.
|
||||
*
|
||||
* Values are indices into colors array. Positive values are filled (lit),
|
||||
* negative values are unfilled (dark / border only). The actual color index
|
||||
* is the absolute value of the value - 1. 0 values are not drawn at all
|
||||
* (an empty space is left).
|
||||
*
|
||||
* @param values values array
|
||||
* @param numValues size of values array
|
||||
* @param cols number of columns
|
||||
* @param colors colors array
|
||||
* @param size size of each LED (both horizontal and vertical)
|
||||
* @param spacing spacing between each LED (both horizontal and vertical)
|
||||
*/
|
||||
void DrawLEDs(int* values, int numValues, int cols, const ImU32* colors,
|
||||
float size = 8.0f, float spacing = 6.0f);
|
||||
|
||||
} // namespace halsimgui
|
||||
132
simulation/halsim_gui/src/main/native/include/HALSimGui.h
Normal file
132
simulation/halsim_gui/src/main/native/include/HALSimGui.h
Normal file
@@ -0,0 +1,132 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#ifdef __cplusplus
|
||||
#include <functional>
|
||||
#endif
|
||||
|
||||
extern "C" {
|
||||
|
||||
void HALSIMGUI_Add(void* param, void (*initialize)(void*));
|
||||
void HALSIMGUI_AddExecute(void* param, void (*execute)(void*));
|
||||
void HALSIMGUI_AddWindow(const char* name, void* param, void (*display)(void*),
|
||||
int32_t flags);
|
||||
void HALSIMGUI_AddMainMenu(void* param, void (*menu)(void*));
|
||||
void HALSIMGUI_AddOptionMenu(void* param, void (*menu)(void*));
|
||||
void HALSIMGUI_SetWindowVisibility(const char* name, int32_t visibility);
|
||||
void HALSIMGUI_SetDefaultWindowPos(const char* name, float x, float y);
|
||||
void HALSIMGUI_SetDefaultWindowSize(const char* name, float width,
|
||||
float height);
|
||||
|
||||
} // extern "C"
|
||||
|
||||
#ifdef __cplusplus
|
||||
|
||||
namespace halsimgui {
|
||||
|
||||
class HALSimGui {
|
||||
public:
|
||||
static bool Initialize();
|
||||
static void Main(void*);
|
||||
static void Exit(void*);
|
||||
|
||||
/**
|
||||
* Adds feature to GUI. The initialize function is called once, immediately
|
||||
* after the GUI (both GLFW and Dear ImGui) are initialized.
|
||||
*
|
||||
* @param initialize initialization function
|
||||
* @param execute frame execution function
|
||||
*/
|
||||
static void Add(std::function<void()> initialize);
|
||||
|
||||
/**
|
||||
* Adds per-frame executor to GUI. The passed function is called on each
|
||||
* Dear ImGui frame prior to window and menu functions.
|
||||
*
|
||||
* @param execute frame execution function
|
||||
*/
|
||||
static void AddExecute(std::function<void()> execute);
|
||||
|
||||
/**
|
||||
* Adds window to GUI. The display function is called from within a
|
||||
* ImGui::Begin()/End() block. While windows can be created within the
|
||||
* execute function passed to AddExecute(), using this function ensures the
|
||||
* windows are consistently integrated with the rest of the GUI.
|
||||
*
|
||||
* On each Dear ImGui frame, AddExecute() functions are always called prior
|
||||
* to AddWindow display functions. Note that windows may be shaded or
|
||||
* completely hidden, in which case this function will not be called.
|
||||
* It's important to perform any processing steps that must be performed
|
||||
* every frame in the AddExecute() function.
|
||||
*
|
||||
* @param name name of the window (title bar)
|
||||
* @param display window contents display function
|
||||
* @param flags Dear ImGui window flags
|
||||
*/
|
||||
static void AddWindow(const char* name, std::function<void()> display,
|
||||
int flags = 0);
|
||||
|
||||
/**
|
||||
* Adds to GUI's main menu bar. The menu function is called from within a
|
||||
* ImGui::BeginMainMenuBar()/EndMainMenuBar() block. Usually it's only
|
||||
* appropriate to create a menu with ImGui::BeginMenu()/EndMenu() inside of
|
||||
* this function.
|
||||
*
|
||||
* On each Dear ImGui frame, AddExecute() functions are always called prior
|
||||
* to AddMainMenu menu functions.
|
||||
*
|
||||
* @param menu menu display function
|
||||
*/
|
||||
static void AddMainMenu(std::function<void()> menu);
|
||||
|
||||
/**
|
||||
* Adds to GUI's option menu. The menu function is called from within a
|
||||
* ImGui::BeginMenu()/EndMenu() block. Usually it's only appropriate to
|
||||
* create menu items inside of this function.
|
||||
*
|
||||
* On each Dear ImGui frame, AddExecute() functions are always called prior
|
||||
* to AddMainMenu menu functions.
|
||||
*
|
||||
* @param menu menu display function
|
||||
*/
|
||||
static void AddOptionMenu(std::function<void()> menu);
|
||||
|
||||
enum WindowVisibility { kHide = 0, kShow, kDisabled };
|
||||
|
||||
/**
|
||||
* Sets visibility of window added with AddWindow().
|
||||
*
|
||||
* @param name window name (same as name passed to AddWindow())
|
||||
* @param visibility 0=hide, 1=show, 2=disabled (force-hide)
|
||||
*/
|
||||
static void SetWindowVisibility(const char* name,
|
||||
WindowVisibility visibility);
|
||||
|
||||
/**
|
||||
* Sets default position of window added with AddWindow().
|
||||
*
|
||||
* @param name window name (same as name passed to AddWindow())
|
||||
* @param x x location of upper left corner
|
||||
* @param y y location of upper left corner
|
||||
*/
|
||||
static void SetDefaultWindowPos(const char* name, float x, float y);
|
||||
|
||||
/**
|
||||
* Sets default size of window added with AddWindow().
|
||||
*
|
||||
* @param name window name (same as name passed to AddWindow())
|
||||
* @param width width
|
||||
* @param height height
|
||||
*/
|
||||
static void SetDefaultWindowSize(const char* name, float width, float height);
|
||||
};
|
||||
|
||||
} // namespace halsimgui
|
||||
|
||||
#endif // __cplusplus
|
||||
91
simulation/halsim_gui/src/main/native/include/SimDeviceGui.h
Normal file
91
simulation/halsim_gui/src/main/native/include/SimDeviceGui.h
Normal file
@@ -0,0 +1,91 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <hal/Types.h>
|
||||
#include <hal/Value.h>
|
||||
|
||||
#ifdef __cplusplus
|
||||
#include <functional>
|
||||
|
||||
#include <imgui.h>
|
||||
#endif
|
||||
|
||||
extern "C" {
|
||||
|
||||
void HALSIMGUI_DeviceTreeHide(const char* name);
|
||||
void HALSIMGUI_DeviceTreeAdd(void* param, void (*execute)(void*));
|
||||
HAL_Bool HALSIMGUI_DeviceTreeDisplayValue(const char* name, HAL_Bool readonly,
|
||||
struct HAL_Value* value,
|
||||
const char** options,
|
||||
int32_t numOptions);
|
||||
HAL_Bool HALSIMGUI_DeviceTreeStartDevice(const char* label, int32_t flags);
|
||||
void HALSIMGUI_DeviceTreeFinishDevice(void);
|
||||
|
||||
} // extern "C"
|
||||
|
||||
#ifdef __cplusplus
|
||||
|
||||
namespace halsimgui {
|
||||
|
||||
class SimDeviceGui {
|
||||
public:
|
||||
static void Initialize();
|
||||
|
||||
/**
|
||||
* Hides device on tree.
|
||||
*
|
||||
* @param name device name
|
||||
*/
|
||||
static void Hide(const char* name);
|
||||
|
||||
/**
|
||||
* Adds device to tree. The execute function is called from within the
|
||||
* device tree window context on every frame, so it should implement an
|
||||
* TreeNodeEx() block for each device to display.
|
||||
*
|
||||
* @param execute execute function
|
||||
*/
|
||||
static void Add(std::function<void()> execute);
|
||||
|
||||
/**
|
||||
* Displays device value formatted the same way as SimDevice device values.
|
||||
*
|
||||
* @param name value name
|
||||
* @param readonly prevent value from being modified by the user
|
||||
* @param value value contents (modified in place)
|
||||
* @param options options array for enum values
|
||||
* @param numOptions size of options array for enum values
|
||||
* @return True if value was modified by the user
|
||||
*/
|
||||
static bool DisplayValue(const char* name, bool readonly, HAL_Value* value,
|
||||
const char** options = nullptr,
|
||||
int32_t numOptions = 0);
|
||||
|
||||
/**
|
||||
* Wraps ImGui::CollapsingHeader() to provide consistency and open
|
||||
* persistence. As with the ImGui function, returns true if the tree node
|
||||
* is expanded. If returns true, call StopDevice() to finish the block.
|
||||
*
|
||||
* @param label label
|
||||
* @param flags ImGuiTreeNodeFlags flags
|
||||
* @return True if expanded
|
||||
*/
|
||||
static bool StartDevice(const char* label, ImGuiTreeNodeFlags flags = 0);
|
||||
|
||||
/**
|
||||
* Finish a device block started with StartDevice().
|
||||
*/
|
||||
static void FinishDevice();
|
||||
};
|
||||
|
||||
} // namespace halsimgui
|
||||
|
||||
#endif // __cplusplus
|
||||
17
simulation/halsim_gui/src/test/native/cpp/main.cpp
Normal file
17
simulation/halsim_gui/src/test/native/cpp/main.cpp
Normal file
@@ -0,0 +1,17 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2015-2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <hal/HAL.h>
|
||||
|
||||
#include "gtest/gtest.h"
|
||||
|
||||
int main(int argc, char** argv) {
|
||||
HAL_Initialize(500, 0);
|
||||
::testing::InitGoogleTest(&argc, argv);
|
||||
int ret = RUN_ALL_TESTS();
|
||||
return ret;
|
||||
}
|
||||
Reference in New Issue
Block a user