blob: 78c286c5f4063c6644ef6f6b74794e5f4db03502 [file] [log] [blame]
Austin Schuh812d0d12021-11-04 20:16:48 -07001// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
Brian Silverman8fce7482020-01-05 13:18:21 -08004
5#include "frc/RobotBase.h"
6
7#ifdef __FRC_ROBORIO__
8#include <dlfcn.h>
9#endif
10
11#include <cstdio>
12
13#include <cameraserver/CameraServerShared.h>
Austin Schuh812d0d12021-11-04 20:16:48 -070014#include <fmt/format.h>
Brian Silverman8fce7482020-01-05 13:18:21 -080015#include <hal/FRCUsageReporting.h>
16#include <hal/HALBase.h>
17#include <networktables/NetworkTableInstance.h>
Austin Schuh1e69f942020-11-14 15:06:14 -080018#include <wpimath/MathShared.h>
Brian Silverman8fce7482020-01-05 13:18:21 -080019
20#include "WPILibVersion.h"
21#include "frc/DriverStation.h"
Austin Schuh812d0d12021-11-04 20:16:48 -070022#include "frc/Errors.h"
23#include "frc/Notifier.h"
Brian Silverman8fce7482020-01-05 13:18:21 -080024#include "frc/RobotState.h"
Brian Silverman8fce7482020-01-05 13:18:21 -080025#include "frc/livewindow/LiveWindow.h"
26#include "frc/smartdashboard/SmartDashboard.h"
27
Austin Schuh812d0d12021-11-04 20:16:48 -070028static_assert(frc::RuntimeType::kRoboRIO ==
29 static_cast<frc::RuntimeType>(HAL_Runtime_RoboRIO));
30static_assert(frc::RuntimeType::kRoboRIO2 ==
31 static_cast<frc::RuntimeType>(HAL_Runtime_RoboRIO2));
32static_assert(frc::RuntimeType::kSimulation ==
33 static_cast<frc::RuntimeType>(HAL_Runtime_Simulation));
34
35using SetCameraServerSharedFP = void (*)(frc::CameraServerShared*);
Brian Silverman8fce7482020-01-05 13:18:21 -080036
37using namespace frc;
38
39int frc::RunHALInitialization() {
40 if (!HAL_Initialize(500, 0)) {
Austin Schuh812d0d12021-11-04 20:16:48 -070041 std::puts("FATAL ERROR: HAL could not be initialized");
Brian Silverman8fce7482020-01-05 13:18:21 -080042 return -1;
43 }
44 HAL_Report(HALUsageReporting::kResourceType_Language,
45 HALUsageReporting::kLanguage_CPlusPlus, 0, GetWPILibVersion());
Austin Schuh812d0d12021-11-04 20:16:48 -070046
47 if (!frc::Notifier::SetHALThreadPriority(true, 40)) {
48 FRC_ReportError(warn::Warning, "{}",
49 "Setting HAL Notifier RT priority to 40 failed\n");
50 }
51
52 std::puts("\n********** Robot program starting **********");
Brian Silverman8fce7482020-01-05 13:18:21 -080053 return 0;
54}
55
56std::thread::id RobotBase::m_threadId;
57
58namespace {
59class WPILibCameraServerShared : public frc::CameraServerShared {
60 public:
61 void ReportUsbCamera(int id) override {
62 HAL_Report(HALUsageReporting::kResourceType_UsbCamera, id);
63 }
64 void ReportAxisCamera(int id) override {
65 HAL_Report(HALUsageReporting::kResourceType_AxisCamera, id);
66 }
67 void ReportVideoServer(int id) override {
68 HAL_Report(HALUsageReporting::kResourceType_PCVideoServer, id);
69 }
Austin Schuh812d0d12021-11-04 20:16:48 -070070 void SetCameraServerErrorV(fmt::string_view format,
71 fmt::format_args args) override {
72 ReportErrorV(err::CameraServerError, __FILE__, __LINE__, __FUNCTION__,
73 format, args);
Brian Silverman8fce7482020-01-05 13:18:21 -080074 }
Austin Schuh812d0d12021-11-04 20:16:48 -070075 void SetVisionRunnerErrorV(fmt::string_view format,
76 fmt::format_args args) override {
77 ReportErrorV(err::Error, __FILE__, __LINE__, __FUNCTION__, format, args);
Brian Silverman8fce7482020-01-05 13:18:21 -080078 }
Austin Schuh812d0d12021-11-04 20:16:48 -070079 void ReportDriverStationErrorV(fmt::string_view format,
80 fmt::format_args args) override {
81 ReportErrorV(err::Error, __FILE__, __LINE__, __FUNCTION__, format, args);
Brian Silverman8fce7482020-01-05 13:18:21 -080082 }
83 std::pair<std::thread::id, bool> GetRobotMainThreadId() const override {
84 return std::make_pair(RobotBase::GetThreadId(), true);
85 }
86};
Austin Schuh1e69f942020-11-14 15:06:14 -080087class WPILibMathShared : public wpi::math::MathShared {
88 public:
Austin Schuh812d0d12021-11-04 20:16:48 -070089 void ReportErrorV(fmt::string_view format, fmt::format_args args) override {
90 frc::ReportErrorV(err::Error, __FILE__, __LINE__, __FUNCTION__, format,
91 args);
92 }
93
94 void ReportWarningV(fmt::string_view format, fmt::format_args args) override {
95 frc::ReportErrorV(warn::Warning, __FILE__, __LINE__, __FUNCTION__, format,
96 args);
Austin Schuh1e69f942020-11-14 15:06:14 -080097 }
98
99 void ReportUsage(wpi::math::MathUsageId id, int count) override {
100 switch (id) {
101 case wpi::math::MathUsageId::kKinematics_DifferentialDrive:
102 HAL_Report(HALUsageReporting::kResourceType_Kinematics,
103 HALUsageReporting::kKinematics_DifferentialDrive);
104 break;
105 case wpi::math::MathUsageId::kKinematics_MecanumDrive:
106 HAL_Report(HALUsageReporting::kResourceType_Kinematics,
107 HALUsageReporting::kKinematics_MecanumDrive);
108 break;
109 case wpi::math::MathUsageId::kKinematics_SwerveDrive:
110 HAL_Report(HALUsageReporting::kResourceType_Kinematics,
111 HALUsageReporting::kKinematics_SwerveDrive);
112 break;
113 case wpi::math::MathUsageId::kTrajectory_TrapezoidProfile:
114 HAL_Report(HALUsageReporting::kResourceType_TrapezoidProfile, count);
115 break;
116 case wpi::math::MathUsageId::kFilter_Linear:
117 HAL_Report(HALUsageReporting::kResourceType_LinearFilter, count);
118 break;
119 case wpi::math::MathUsageId::kOdometry_DifferentialDrive:
120 HAL_Report(HALUsageReporting::kResourceType_Odometry,
121 HALUsageReporting::kOdometry_DifferentialDrive);
122 break;
123 case wpi::math::MathUsageId::kOdometry_SwerveDrive:
124 HAL_Report(HALUsageReporting::kResourceType_Odometry,
125 HALUsageReporting::kOdometry_SwerveDrive);
126 break;
127 case wpi::math::MathUsageId::kOdometry_MecanumDrive:
128 HAL_Report(HALUsageReporting::kResourceType_Odometry,
129 HALUsageReporting::kOdometry_MecanumDrive);
130 break;
Austin Schuh812d0d12021-11-04 20:16:48 -0700131 case wpi::math::MathUsageId::kController_PIDController2:
132 HAL_Report(HALUsageReporting::kResourceType_PIDController2, count);
133 break;
134 case wpi::math::MathUsageId::kController_ProfiledPIDController:
135 HAL_Report(HALUsageReporting::kResourceType_ProfiledPIDController,
136 count);
137 break;
Austin Schuh1e69f942020-11-14 15:06:14 -0800138 }
139 }
140};
Brian Silverman8fce7482020-01-05 13:18:21 -0800141} // namespace
142
143static void SetupCameraServerShared() {
144#ifdef __FRC_ROBORIO__
145#ifdef DYNAMIC_CAMERA_SERVER
146#ifdef DYNAMIC_CAMERA_SERVER_DEBUG
147 auto cameraServerLib = dlopen("libcameraserverd.so", RTLD_NOW);
148#else
149 auto cameraServerLib = dlopen("libcameraserver.so", RTLD_NOW);
150#endif
151
152 if (!cameraServerLib) {
Austin Schuh812d0d12021-11-04 20:16:48 -0700153 std::puts("Camera Server Library Not Found");
154 std::fflush(stdout);
Brian Silverman8fce7482020-01-05 13:18:21 -0800155 return;
156 }
157 auto symbol = dlsym(cameraServerLib, "CameraServer_SetCameraServerShared");
158 if (symbol) {
159 auto setCameraServerShared = (SetCameraServerSharedFP)symbol;
160 setCameraServerShared(new WPILibCameraServerShared{});
Brian Silverman8fce7482020-01-05 13:18:21 -0800161 } else {
Austin Schuh812d0d12021-11-04 20:16:48 -0700162 std::puts("Camera Server Shared Symbol Missing");
163 std::fflush(stdout);
Brian Silverman8fce7482020-01-05 13:18:21 -0800164 }
165#else
166 CameraServer_SetCameraServerShared(new WPILibCameraServerShared{});
167#endif
168#else
Austin Schuh812d0d12021-11-04 20:16:48 -0700169 std::puts("Not loading CameraServerShared");
170 std::fflush(stdout);
Brian Silverman8fce7482020-01-05 13:18:21 -0800171#endif
172}
173
Austin Schuh1e69f942020-11-14 15:06:14 -0800174static void SetupMathShared() {
175 wpi::math::MathSharedStore::SetMathShared(
176 std::make_unique<WPILibMathShared>());
177}
178
Austin Schuh812d0d12021-11-04 20:16:48 -0700179bool RobotBase::IsEnabled() const {
180 return DriverStation::IsEnabled();
181}
Brian Silverman8fce7482020-01-05 13:18:21 -0800182
Austin Schuh812d0d12021-11-04 20:16:48 -0700183bool RobotBase::IsDisabled() const {
184 return DriverStation::IsDisabled();
185}
Brian Silverman8fce7482020-01-05 13:18:21 -0800186
Austin Schuh812d0d12021-11-04 20:16:48 -0700187bool RobotBase::IsAutonomous() const {
188 return DriverStation::IsAutonomous();
189}
Brian Silverman8fce7482020-01-05 13:18:21 -0800190
Austin Schuh1e69f942020-11-14 15:06:14 -0800191bool RobotBase::IsAutonomousEnabled() const {
Austin Schuh812d0d12021-11-04 20:16:48 -0700192 return DriverStation::IsAutonomousEnabled();
Austin Schuh1e69f942020-11-14 15:06:14 -0800193}
194
Austin Schuh812d0d12021-11-04 20:16:48 -0700195bool RobotBase::IsOperatorControl() const {
196 return DriverStation::IsTeleop();
197}
198
199bool RobotBase::IsTeleop() const {
200 return DriverStation::IsTeleop();
201}
Brian Silverman8fce7482020-01-05 13:18:21 -0800202
Austin Schuh1e69f942020-11-14 15:06:14 -0800203bool RobotBase::IsOperatorControlEnabled() const {
Austin Schuh812d0d12021-11-04 20:16:48 -0700204 return DriverStation::IsTeleopEnabled();
Austin Schuh1e69f942020-11-14 15:06:14 -0800205}
206
Austin Schuh812d0d12021-11-04 20:16:48 -0700207bool RobotBase::IsTeleopEnabled() const {
208 return DriverStation::IsTeleopEnabled();
209}
Brian Silverman8fce7482020-01-05 13:18:21 -0800210
Austin Schuh812d0d12021-11-04 20:16:48 -0700211bool RobotBase::IsTest() const {
212 return DriverStation::IsTest();
213}
Brian Silverman8fce7482020-01-05 13:18:21 -0800214
Austin Schuh812d0d12021-11-04 20:16:48 -0700215bool RobotBase::IsNewDataAvailable() const {
216 return DriverStation::IsNewControlData();
217}
Brian Silverman8fce7482020-01-05 13:18:21 -0800218
Austin Schuh812d0d12021-11-04 20:16:48 -0700219std::thread::id RobotBase::GetThreadId() {
220 return m_threadId;
221}
222
223RuntimeType RobotBase::GetRuntimeType() {
224 return static_cast<RuntimeType>(HAL_GetRuntimeType());
225}
226
227RobotBase::RobotBase() {
Brian Silverman8fce7482020-01-05 13:18:21 -0800228 m_threadId = std::this_thread::get_id();
229
230 SetupCameraServerShared();
Austin Schuh1e69f942020-11-14 15:06:14 -0800231 SetupMathShared();
Brian Silverman8fce7482020-01-05 13:18:21 -0800232
233 auto inst = nt::NetworkTableInstance::GetDefault();
234 inst.SetNetworkIdentity("Robot");
235#ifdef __FRC_ROBORIO__
236 inst.StartServer("/home/lvuser/networktables.ini");
237#else
238 inst.StartServer();
239#endif
240
241 SmartDashboard::init();
242
243 if (IsReal()) {
244 std::FILE* file = nullptr;
245 file = std::fopen("/tmp/frc_versions/FRC_Lib_Version.ini", "w");
246
247 if (file != nullptr) {
248 std::fputs("C++ ", file);
249 std::fputs(GetWPILibVersion(), file);
250 std::fclose(file);
251 }
252 }
253
254 // First and one-time initialization
255 inst.GetTable("LiveWindow")
256 ->GetSubTable(".status")
257 ->GetEntry("LW Enabled")
258 .SetBoolean(false);
259
Austin Schuh812d0d12021-11-04 20:16:48 -0700260 LiveWindow::SetEnabled(false);
Brian Silverman8fce7482020-01-05 13:18:21 -0800261}