2020-07-02 22:02:21 -04:00
/ *
2020-12-31 19:57:51 -08:00
* Copyright ( C ) Photon Vision .
2020-07-02 22:02:21 -04:00
*
* This program is free software : you can redistribute it and / or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation , either version 3 of the License , or
* ( at your option ) any later version .
*
* This program is distributed in the hope that it will be useful ,
* but WITHOUT ANY WARRANTY ; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
* GNU General Public License for more details .
*
* You should have received a copy of the GNU General Public License
* along with this program . If not , see < https : //www.gnu.org/licenses/>.
* /
2022-01-20 19:35:28 -08:00
2020-06-27 14:58:03 -07:00
package org.photonvision.server ;
2024-01-05 21:40:06 -07:00
import com.fasterxml.jackson.annotation.JsonProperty ;
2020-08-14 12:39:21 -07:00
import com.fasterxml.jackson.core.JsonProcessingException ;
2020-06-27 14:58:03 -07:00
import com.fasterxml.jackson.databind.ObjectMapper ;
import io.javalin.http.Context ;
2023-06-25 21:07:27 -04:00
import io.javalin.http.UploadedFile ;
2023-11-05 11:33:45 -05:00
import java.io.* ;
2023-01-03 19:42:19 -08:00
import java.nio.file.Files ;
2020-08-14 12:39:21 -07:00
import java.nio.file.Path ;
2021-12-03 22:08:51 -06:00
import java.nio.file.Paths ;
2023-11-05 11:33:45 -05:00
import java.util.ArrayList ;
import java.util.HashMap ;
2023-06-25 21:07:27 -04:00
import java.util.Optional ;
2023-11-05 11:33:45 -05:00
import javax.imageio.ImageIO ;
2020-08-14 12:39:21 -07:00
import org.apache.commons.io.FileUtils ;
2024-10-13 01:29:17 -04:00
import org.opencv.core.Mat ;
2024-02-01 21:42:54 -05:00
import org.opencv.core.MatOfByte ;
import org.opencv.core.MatOfInt ;
import org.opencv.imgcodecs.Imgcodecs ;
2020-08-14 12:39:21 -07:00
import org.photonvision.common.configuration.ConfigManager ;
import org.photonvision.common.configuration.NetworkConfig ;
2023-01-18 16:29:58 -05:00
import org.photonvision.common.dataflow.DataChangeDestination ;
import org.photonvision.common.dataflow.DataChangeService ;
import org.photonvision.common.dataflow.events.IncomingWebSocketEvent ;
2020-08-14 12:39:21 -07:00
import org.photonvision.common.dataflow.networktables.NetworkTablesManager ;
import org.photonvision.common.hardware.HardwareManager ;
2020-09-04 18:18:44 -07:00
import org.photonvision.common.hardware.Platform ;
2020-08-14 12:39:21 -07:00
import org.photonvision.common.logging.LogGroup ;
import org.photonvision.common.logging.Logger ;
import org.photonvision.common.networking.NetworkManager ;
2020-09-10 19:20:16 -07:00
import org.photonvision.common.util.ShellExec ;
2022-01-09 16:02:32 -08:00
import org.photonvision.common.util.TimedTaskManager ;
2024-01-05 21:40:06 -07:00
import org.photonvision.common.util.file.JacksonUtils ;
2021-12-03 22:08:51 -06:00
import org.photonvision.common.util.file.ProgramDirectoryUtilities ;
2023-01-18 16:29:58 -05:00
import org.photonvision.vision.calibration.CameraCalibrationCoefficients ;
2024-01-05 21:40:06 -07:00
import org.photonvision.vision.camera.CameraQuirk ;
2025-01-01 03:04:20 -05:00
import org.photonvision.vision.camera.PVCameraInfo ;
import org.photonvision.vision.processes.VisionSourceManager ;
2024-11-06 20:16:36 -05:00
import org.zeroturnaround.zip.ZipUtil ;
2020-06-27 14:58:03 -07:00
public class RequestHandler {
2023-06-25 21:07:27 -04:00
// Treat all 2XX calls as "INFO"
// Treat all 4XX calls as "ERROR"
// Treat all 5XX calls as "ERROR"
2020-08-14 12:39:21 -07:00
private static final Logger logger = new Logger ( RequestHandler . class , LogGroup . WebServer ) ;
2020-06-27 14:58:03 -07:00
2020-06-28 04:40:43 -04:00
private static final ObjectMapper kObjectMapper = new ObjectMapper ( ) ;
2023-06-25 21:07:27 -04:00
public static void onSettingsImportRequest ( Context ctx ) {
var file = ctx . uploadedFile ( " data " ) ;
2020-11-07 19:21:07 -06:00
2023-06-25 21:07:27 -04:00
if ( file = = null ) {
ctx . status ( 400 ) ;
ctx . result (
" No File was sent with the request. Make sure that the settings zip is sent at the key 'data' " ) ;
logger . error (
" No File was sent with the request. Make sure that the settings zip is sent at the key 'data' " ) ;
return ;
}
2020-11-07 19:21:07 -06:00
2023-10-05 18:22:56 -04:00
if ( ! file . extension ( ) . contains ( " zip " ) ) {
2023-06-25 21:07:27 -04:00
ctx . status ( 400 ) ;
ctx . result (
" The uploaded file was not of type 'zip'. The uploaded file should be a .zip file. " ) ;
logger . error (
" The uploaded file was not of type 'zip'. The uploaded file should be a .zip file. " ) ;
return ;
}
2020-11-07 19:21:07 -06:00
2023-06-25 21:07:27 -04:00
// Create a temp file
var tempFilePath = handleTempFileCreation ( file ) ;
if ( tempFilePath . isEmpty ( ) ) {
ctx . status ( 500 ) ;
ctx . result ( " There was an error while creating a temporary copy of the file " ) ;
logger . error ( " There was an error while creating a temporary copy of the file " ) ;
return ;
}
2024-10-24 20:48:02 -07:00
ConfigManager . getInstance ( ) . setWriteTaskEnabled ( false ) ;
ConfigManager . getInstance ( ) . disableFlushOnShutdown ( ) ;
// We want to delete the -whole- zip file, so we need to teardown loggers for now
logger . info ( " Writing new settings zip (logs may be truncated)... " ) ;
Logger . closeAllLoggers ( ) ;
2023-06-25 21:07:27 -04:00
if ( ConfigManager . saveUploadedSettingsZip ( tempFilePath . get ( ) ) ) {
2020-09-04 18:18:44 -07:00
ctx . status ( 200 ) ;
2023-12-28 22:36:15 -06:00
ctx . result ( " Successfully saved the uploaded settings zip, rebooting... " ) ;
2023-11-21 23:01:59 -05:00
restartProgram ( ) ;
2020-08-14 12:39:21 -07:00
} else {
2020-09-04 18:18:44 -07:00
ctx . status ( 500 ) ;
2023-06-25 21:07:27 -04:00
ctx . result ( " There was an error while saving the uploaded zip file " ) ;
2020-08-14 12:39:21 -07:00
}
2020-06-28 04:40:43 -04:00
}
2023-06-25 21:07:27 -04:00
public static void onSettingsExportRequest ( Context ctx ) {
logger . info ( " Exporting Settings to ZIP Archive " ) ;
2021-12-03 22:08:51 -06:00
2023-06-25 21:07:27 -04:00
try {
var zip = ConfigManager . getInstance ( ) . getSettingsFolderAsZip ( ) ;
var stream = new FileInputStream ( zip ) ;
logger . info ( " Uploading settings with size " + stream . available ( ) ) ;
2021-12-03 22:08:51 -06:00
2023-06-25 21:07:27 -04:00
ctx . contentType ( " application/zip " ) ;
ctx . header (
" Content-Disposition " , " attachment; filename= \" photonvision-settings-export.zip \" " ) ;
2022-12-26 21:51:34 -06:00
2023-06-25 21:07:27 -04:00
ctx . result ( stream ) ;
ctx . status ( 200 ) ;
} catch ( IOException e ) {
logger . error ( " Unable to export settings archive, bad recode from zip to byte " ) ;
ctx . status ( 500 ) ;
ctx . result ( " There was an error while exporting the settings archive " ) ;
}
}
2022-12-26 21:51:34 -06:00
2023-06-25 21:07:27 -04:00
public static void onHardwareConfigRequest ( Context ctx ) {
var file = ctx . uploadedFile ( " data " ) ;
if ( file = = null ) {
ctx . status ( 400 ) ;
ctx . result (
" No File was sent with the request. Make sure that the hardware config json is sent at the key 'data' " ) ;
logger . error (
" No File was sent with the request. Make sure that the hardware config json is sent at the key 'data' " ) ;
return ;
}
2023-10-05 18:22:56 -04:00
if ( ! file . extension ( ) . contains ( " json " ) ) {
2023-06-25 21:07:27 -04:00
ctx . status ( 400 ) ;
ctx . result (
" The uploaded file was not of type 'json'. The uploaded file should be a .json file. " ) ;
logger . error (
" The uploaded file was not of type 'json'. The uploaded file should be a .json file. " ) ;
return ;
}
// Create a temp file
var tempFilePath = handleTempFileCreation ( file ) ;
if ( tempFilePath . isEmpty ( ) ) {
ctx . status ( 500 ) ;
ctx . result ( " There was an error while creating a temporary copy of the file " ) ;
logger . error ( " There was an error while creating a temporary copy of the file " ) ;
return ;
}
if ( ConfigManager . getInstance ( ) . saveUploadedHardwareConfig ( tempFilePath . get ( ) . toPath ( ) ) ) {
ctx . status ( 200 ) ;
2023-12-28 22:36:15 -06:00
ctx . result ( " Successfully saved the uploaded hardware config, rebooting... " ) ;
logger . info ( " Successfully saved the uploaded hardware config, rebooting... " ) ;
restartProgram ( ) ;
2023-06-25 21:07:27 -04:00
} else {
ctx . status ( 500 ) ;
ctx . result ( " There was an error while saving the uploaded hardware config " ) ;
logger . error ( " There was an error while saving the uploaded hardware config " ) ;
}
}
public static void onHardwareSettingsRequest ( Context ctx ) {
var file = ctx . uploadedFile ( " data " ) ;
if ( file = = null ) {
ctx . status ( 400 ) ;
ctx . result (
" No File was sent with the request. Make sure that the hardware settings json is sent at the key 'data' " ) ;
logger . error (
" No File was sent with the request. Make sure that the hardware settings json is sent at the key 'data' " ) ;
return ;
}
2023-10-05 18:22:56 -04:00
if ( ! file . extension ( ) . contains ( " json " ) ) {
2023-06-25 21:07:27 -04:00
ctx . status ( 400 ) ;
ctx . result (
" The uploaded file was not of type 'json'. The uploaded file should be a .json file. " ) ;
logger . error (
" The uploaded file was not of type 'json'. The uploaded file should be a .json file. " ) ;
return ;
}
// Create a temp file
var tempFilePath = handleTempFileCreation ( file ) ;
if ( tempFilePath . isEmpty ( ) ) {
ctx . status ( 500 ) ;
ctx . result ( " There was an error while creating a temporary copy of the file " ) ;
logger . error ( " There was an error while creating a temporary copy of the file " ) ;
return ;
}
if ( ConfigManager . getInstance ( ) . saveUploadedHardwareSettings ( tempFilePath . get ( ) . toPath ( ) ) ) {
ctx . status ( 200 ) ;
2023-12-28 22:36:15 -06:00
ctx . result ( " Successfully saved the uploaded hardware settings, rebooting... " ) ;
logger . info ( " Successfully saved the uploaded hardware settings, rebooting... " ) ;
restartProgram ( ) ;
2021-12-03 22:08:51 -06:00
} else {
ctx . status ( 500 ) ;
2023-06-25 21:07:27 -04:00
ctx . result ( " There was an error while saving the uploaded hardware settings " ) ;
logger . error ( " There was an error while saving the uploaded hardware settings " ) ;
2021-12-03 22:08:51 -06:00
}
}
2023-06-25 21:07:27 -04:00
public static void onNetworkConfigRequest ( Context ctx ) {
var file = ctx . uploadedFile ( " data " ) ;
if ( file = = null ) {
ctx . status ( 400 ) ;
ctx . result (
" No File was sent with the request. Make sure that the network config json is sent at the key 'data' " ) ;
logger . error (
" No File was sent with the request. Make sure that the network config json is sent at the key 'data' " ) ;
return ;
}
2023-10-05 18:22:56 -04:00
if ( ! file . extension ( ) . contains ( " json " ) ) {
2023-06-25 21:07:27 -04:00
ctx . status ( 400 ) ;
ctx . result (
" The uploaded file was not of type 'json'. The uploaded file should be a .json file. " ) ;
logger . error (
" The uploaded file was not of type 'json'. The uploaded file should be a .json file. " ) ;
return ;
}
// Create a temp file
var tempFilePath = handleTempFileCreation ( file ) ;
if ( tempFilePath . isEmpty ( ) ) {
ctx . status ( 500 ) ;
ctx . result ( " There was an error while creating a temporary copy of the file " ) ;
logger . error ( " There was an error while creating a temporary copy of the file " ) ;
return ;
}
if ( ConfigManager . getInstance ( ) . saveUploadedNetworkConfig ( tempFilePath . get ( ) . toPath ( ) ) ) {
ctx . status ( 200 ) ;
2023-12-28 22:36:15 -06:00
ctx . result ( " Successfully saved the uploaded network config, rebooting... " ) ;
logger . info ( " Successfully saved the uploaded network config, rebooting... " ) ;
restartProgram ( ) ;
2023-06-25 21:07:27 -04:00
} else {
ctx . status ( 500 ) ;
ctx . result ( " There was an error while saving the uploaded network config " ) ;
logger . error ( " There was an error while saving the uploaded network config " ) ;
}
}
2023-10-17 10:20:00 -04:00
public static void onAprilTagFieldLayoutRequest ( Context ctx ) {
var file = ctx . uploadedFile ( " data " ) ;
if ( file = = null ) {
ctx . status ( 400 ) ;
ctx . result (
" No File was sent with the request. Make sure that the field layout json is sent at the key 'data' " ) ;
logger . error (
" No File was sent with the request. Make sure that the field layout json is sent at the key 'data' " ) ;
return ;
}
if ( ! file . extension ( ) . contains ( " json " ) ) {
ctx . status ( 400 ) ;
ctx . result (
" The uploaded file was not of type 'json'. The uploaded file should be a .json file. " ) ;
logger . error (
" The uploaded file was not of type 'json'. The uploaded file should be a .json file. " ) ;
return ;
}
// Create a temp file
var tempFilePath = handleTempFileCreation ( file ) ;
if ( tempFilePath . isEmpty ( ) ) {
ctx . status ( 500 ) ;
ctx . result ( " There was an error while creating a temporary copy of the file " ) ;
logger . error ( " There was an error while creating a temporary copy of the file " ) ;
return ;
}
if ( ConfigManager . getInstance ( ) . saveUploadedAprilTagFieldLayout ( tempFilePath . get ( ) . toPath ( ) ) ) {
ctx . status ( 200 ) ;
2023-12-28 22:36:15 -06:00
ctx . result ( " Successfully saved the uploaded AprilTagFieldLayout, rebooting... " ) ;
logger . info ( " Successfully saved the uploaded AprilTagFieldLayout, rebooting... " ) ;
restartProgram ( ) ;
2023-10-17 10:20:00 -04:00
} else {
ctx . status ( 500 ) ;
ctx . result ( " There was an error while saving the uploaded AprilTagFieldLayout " ) ;
logger . error ( " There was an error while saving the uploaded AprilTagFieldLayout " ) ;
}
}
2023-06-25 21:07:27 -04:00
public static void onOfflineUpdateRequest ( Context ctx ) {
var file = ctx . uploadedFile ( " jarData " ) ;
if ( file = = null ) {
ctx . status ( 400 ) ;
ctx . result (
" No File was sent with the request. Make sure that the new jar is sent at the key 'jarData' " ) ;
logger . error (
" No File was sent with the request. Make sure that the new jar is sent at the key 'jarData' " ) ;
return ;
}
2023-10-05 18:22:56 -04:00
if ( ! file . extension ( ) . contains ( " jar " ) ) {
2023-06-25 21:07:27 -04:00
ctx . status ( 400 ) ;
ctx . result (
" The uploaded file was not of type 'jar'. The uploaded file should be a .jar file. " ) ;
logger . error (
" The uploaded file was not of type 'jar'. The uploaded file should be a .jar file. " ) ;
return ;
}
try {
Path filePath =
Paths . get ( ProgramDirectoryUtilities . getProgramDirectory ( ) , " photonvision.jar " ) ;
File targetFile = new File ( filePath . toString ( ) ) ;
var stream = new FileOutputStream ( targetFile ) ;
2023-10-05 18:22:56 -04:00
file . content ( ) . transferTo ( stream ) ;
2023-06-25 21:07:27 -04:00
stream . close ( ) ;
2020-08-14 12:39:21 -07:00
2023-06-25 21:07:27 -04:00
ctx . status ( 200 ) ;
ctx . result (
" Offline update successfully complete. PhotonVision will restart in the background. " ) ;
logger . info (
" Offline update successfully complete. PhotonVision will restart in the background. " ) ;
restartProgram ( ) ;
} catch ( FileNotFoundException e ) {
ctx . result ( " The current program jar file couldn't be found. " ) ;
ctx . status ( 500 ) ;
logger . error ( " The current program jar file couldn't be found. " , e ) ;
} catch ( IOException e ) {
ctx . result ( " Unable to overwrite the existing program with the new program. " ) ;
ctx . status ( 500 ) ;
logger . error ( " Unable to overwrite the existing program with the new program. " , e ) ;
}
}
public static void onGeneralSettingsRequest ( Context ctx ) {
NetworkConfig config ;
try {
2024-05-10 14:58:18 -04:00
config = kObjectMapper . readValue ( ctx . bodyInputStream ( ) , NetworkConfig . class ) ;
2023-06-25 21:07:27 -04:00
ctx . status ( 200 ) ;
ctx . result ( " Successfully saved general settings " ) ;
logger . info ( " Successfully saved general settings " ) ;
2024-05-10 14:58:18 -04:00
} catch ( IOException e ) {
2023-06-25 21:07:27 -04:00
// If the settings can't be parsed, use the default network settings
config = new NetworkConfig ( ) ;
ctx . status ( 400 ) ;
ctx . result ( " The provided general settings were malformed " ) ;
logger . error ( " The provided general settings were malformed " , e ) ;
}
ConfigManager . getInstance ( ) . setNetworkSettings ( config ) ;
2020-08-17 13:25:28 -07:00
ConfigManager . getInstance ( ) . requestSave ( ) ;
2023-06-25 21:07:27 -04:00
2020-08-14 12:39:21 -07:00
NetworkManager . getInstance ( ) . reinitialize ( ) ;
2020-06-28 04:40:43 -04:00
2023-06-25 21:07:27 -04:00
NetworkTablesManager . getInstance ( ) . setConfig ( config ) ;
2020-06-28 04:40:43 -04:00
}
2024-01-05 21:40:06 -07:00
public static class UICameraSettingsRequest {
@JsonProperty ( " fov " )
double fov ;
@JsonProperty ( " quirksToChange " )
HashMap < CameraQuirk , Boolean > quirksToChange ;
}
2023-06-25 21:07:27 -04:00
public static void onCameraSettingsRequest ( Context ctx ) {
2020-08-14 12:39:21 -07:00
try {
2024-05-10 14:58:18 -04:00
var data = kObjectMapper . readTree ( ctx . bodyInputStream ( ) ) ;
2020-08-14 12:39:21 -07:00
2025-01-03 18:50:25 -05:00
String cameraUniqueName = data . get ( " cameraUniqueName " ) . asText ( ) ;
2024-01-05 21:40:06 -07:00
var settings =
JacksonUtils . deserialize ( data . get ( " settings " ) . toString ( ) , UICameraSettingsRequest . class ) ;
var fov = settings . fov ;
logger . info ( " Changing camera FOV to: " + fov ) ;
logger . info ( " Changing quirks to: " + settings . quirksToChange . toString ( ) ) ;
2020-08-14 12:39:21 -07:00
2025-01-03 18:50:25 -05:00
var module = VisionSourceManager . getInstance ( ) . vmm . getModule ( cameraUniqueName ) ;
2022-10-17 11:41:57 -05:00
module . setFov ( fov ) ;
2024-01-05 21:40:06 -07:00
module . changeCameraQuirks ( settings . quirksToChange ) ;
2023-06-25 21:07:27 -04:00
2020-08-14 12:39:21 -07:00
module . saveModule ( ) ;
2020-06-28 04:40:43 -04:00
2020-08-14 12:39:21 -07:00
ctx . status ( 200 ) ;
2023-06-25 21:07:27 -04:00
ctx . result ( " Successfully saved camera settings " ) ;
logger . info ( " Successfully saved camera settings " ) ;
2024-01-05 21:40:06 -07:00
} catch ( NullPointerException | IOException e ) {
2023-06-25 21:07:27 -04:00
ctx . status ( 400 ) ;
ctx . result ( " The provided camera settings were malformed " ) ;
logger . error ( " The provided camera settings were malformed " , e ) ;
2020-08-14 12:39:21 -07:00
}
2020-06-28 04:40:43 -04:00
}
2023-06-25 21:07:27 -04:00
public static void onLogExportRequest ( Context ctx ) {
2023-01-03 19:42:19 -08:00
if ( ! Platform . isLinux ( ) ) {
2023-06-25 21:07:27 -04:00
ctx . status ( 405 ) ;
ctx . result ( " Logs can only be exported on a Linux platform " ) ;
// INFO only log because this isn't ERROR worthy
logger . info ( " Logs can only be exported on a Linux platform " ) ;
2023-01-03 19:42:19 -08:00
return ;
}
try {
2023-06-25 21:07:27 -04:00
ShellExec shell = new ShellExec ( ) ;
2023-01-03 19:42:19 -08:00
var tempPath = Files . createTempFile ( " photonvision-journalctl " , " .txt " ) ;
2024-11-06 20:16:36 -05:00
var tempPath2 = Files . createTempFile ( " photonvision-kernelogs " , " .txt " ) ;
2024-11-11 23:41:22 -06:00
// In the command below:
2025-01-03 18:50:25 -05:00
// dmesg = output all kernel logs since current boot
// cat /var/log/kern.log = output all kernal logs since first boot
2024-11-06 20:16:36 -05:00
shell . executeBashCommand (
" journalctl -u photonvision.service > "
+ tempPath . toAbsolutePath ( )
2024-11-11 23:41:22 -06:00
+ " && dmesg > "
2024-11-06 20:16:36 -05:00
+ tempPath2 . toAbsolutePath ( ) ) ;
2023-01-03 19:42:19 -08:00
while ( ! shell . isOutputCompleted ( ) ) {
// TODO: add timeout
}
if ( shell . getExitCode ( ) = = 0 ) {
2024-11-06 20:16:36 -05:00
// Wrote to the temp file! Zip and yeet it to the client
var out = Files . createTempFile ( " photonvision-logs " , " zip " ) . toFile ( ) ;
try {
ZipUtil . packEntries ( new File [ ] { tempPath . toFile ( ) , tempPath2 . toFile ( ) } , out ) ;
} catch ( Exception e ) {
e . printStackTrace ( ) ;
}
var stream = new FileInputStream ( out ) ;
ctx . contentType ( " application/zip " ) ;
ctx . header ( " Content-Disposition " , " attachment; filename= \" photonvision-logs.zip \" " ) ;
2023-06-25 21:07:27 -04:00
ctx . result ( stream ) ;
2024-11-06 20:16:36 -05:00
ctx . status ( 200 ) ;
logger . info ( " Outputting log ZIP with size " + stream . available ( ) ) ;
2023-01-03 19:42:19 -08:00
} else {
ctx . status ( 500 ) ;
2023-06-25 21:07:27 -04:00
ctx . result ( " The journalctl service was unable to export logs " ) ;
logger . error ( " The journalctl service was unable to export logs " ) ;
2023-01-03 19:42:19 -08:00
}
} catch ( IOException e ) {
ctx . status ( 500 ) ;
2023-06-25 21:07:27 -04:00
ctx . result ( " There was an error while exporting journactl logs " ) ;
logger . error ( " There was an error while exporting journactl logs " , e ) ;
2023-01-03 19:42:19 -08:00
}
}
2023-06-25 21:07:27 -04:00
public static void onCalibrationEndRequest ( Context ctx ) {
2020-11-21 18:14:27 -08:00
logger . info ( " Calibrating camera! This will take a long time... " ) ;
2023-06-09 13:09:41 -04:00
2025-01-03 18:50:25 -05:00
String cameraUniqueName ;
2023-06-25 21:07:27 -04:00
2023-06-09 13:09:41 -04:00
try {
2025-01-03 18:50:25 -05:00
cameraUniqueName =
kObjectMapper . readTree ( ctx . bodyInputStream ( ) ) . get ( " cameraUniqueName " ) . asText ( ) ;
2023-06-25 21:07:27 -04:00
2025-01-03 18:50:25 -05:00
var calData =
VisionSourceManager . getInstance ( ) . vmm . getModule ( cameraUniqueName ) . endCalibration ( ) ;
2023-06-25 21:07:27 -04:00
if ( calData = = null ) {
ctx . result ( " The calibration process failed " ) ;
ctx . status ( 500 ) ;
logger . error (
2025-01-03 18:50:25 -05:00
" The calibration process failed. Calibration data for module at cameraUniqueName ( "
+ cameraUniqueName
2023-06-25 21:07:27 -04:00
+ " ) was null " ) ;
return ;
}
ctx . result ( " Camera calibration successfully completed! " ) ;
ctx . status ( 200 ) ;
logger . info ( " Camera calibration successfully completed! " ) ;
} catch ( JsonProcessingException e ) {
ctx . status ( 400 ) ;
ctx . result (
2025-01-03 18:50:25 -05:00
" The 'cameraUniqueName' field was not found in the request. Please make sure the cameraUniqueName of the vision module is specified with the 'cameraUniqueName' key. " ) ;
2023-06-25 21:07:27 -04:00
logger . error (
2025-01-03 18:50:25 -05:00
" The 'cameraUniqueName' field was not found in the request. Please make sure the cameraUniqueName of the vision module is specified with the 'cameraUniqueName' key. " ,
2023-06-25 21:07:27 -04:00
e ) ;
2023-06-09 13:09:41 -04:00
} catch ( Exception e ) {
ctx . status ( 500 ) ;
2023-06-25 21:07:27 -04:00
ctx . result ( " There was an error while ending calibration " ) ;
logger . error ( " There was an error while ending calibration " , e ) ;
2023-06-09 13:09:41 -04:00
}
2020-06-28 04:40:43 -04:00
}
2024-01-03 14:32:04 -07:00
public static void onDataCalibrationImportRequest ( Context ctx ) {
try {
2024-05-10 14:58:18 -04:00
var data = kObjectMapper . readTree ( ctx . bodyInputStream ( ) ) ;
2024-01-03 14:32:04 -07:00
2025-01-03 18:50:25 -05:00
String cameraUniqueName = data . get ( " cameraUniqueName " ) . asText ( ) ;
2024-01-03 14:32:04 -07:00
var coeffs =
kObjectMapper . convertValue ( data . get ( " calibration " ) , CameraCalibrationCoefficients . class ) ;
var uploadCalibrationEvent =
new IncomingWebSocketEvent < > (
DataChangeDestination . DCD_ACTIVEMODULE ,
" calibrationUploaded " ,
coeffs ,
2025-01-03 18:50:25 -05:00
cameraUniqueName ,
2024-01-03 14:32:04 -07:00
null ) ;
DataChangeService . getInstance ( ) . publishEvent ( uploadCalibrationEvent ) ;
ctx . status ( 200 ) ;
ctx . result ( " Calibration imported successfully from imported data! " ) ;
logger . info ( " Calibration imported successfully from imported data! " ) ;
} catch ( JsonProcessingException e ) {
ctx . status ( 400 ) ;
ctx . result ( " The provided calibration data was malformed " ) ;
logger . error ( " The provided calibration data was malformed " , e ) ;
} catch ( Exception e ) {
ctx . status ( 500 ) ;
ctx . result ( " An error occurred while uploading calibration data " ) ;
logger . error ( " An error occurred while uploading calibration data " , e ) ;
}
}
2023-06-25 21:07:27 -04:00
public static void onProgramRestartRequest ( Context ctx ) {
// TODO, check if this was successful or not
ctx . status ( 204 ) ;
restartProgram ( ) ;
}
2023-01-18 16:29:58 -05:00
2023-06-25 21:07:27 -04:00
public static void onDeviceRestartRequest ( Context ctx ) {
ctx . status ( HardwareManager . getInstance ( ) . restartDevice ( ) ? 204 : 500 ) ;
}
2023-01-18 16:29:58 -05:00
2023-06-25 21:07:27 -04:00
public static void onCameraNicknameChangeRequest ( Context ctx ) {
try {
2024-05-10 14:58:18 -04:00
var data = kObjectMapper . readTree ( ctx . bodyInputStream ( ) ) ;
2023-01-18 16:29:58 -05:00
2023-06-25 21:07:27 -04:00
String name = data . get ( " name " ) . asText ( ) ;
2025-01-03 18:50:25 -05:00
String cameraUniqueName = data . get ( " cameraUniqueName " ) . asText ( ) ;
2023-01-18 16:29:58 -05:00
2025-01-03 18:50:25 -05:00
VisionSourceManager . getInstance ( ) . vmm . getModule ( cameraUniqueName ) . setCameraNickname ( name ) ;
2023-06-25 21:07:27 -04:00
ctx . status ( 200 ) ;
ctx . result ( " Successfully changed the camera name to: " + name ) ;
logger . info ( " Successfully changed the camera name to: " + name ) ;
} catch ( JsonProcessingException e ) {
ctx . status ( 400 ) ;
ctx . result ( " The provided nickname data was malformed " ) ;
logger . error ( " The provided nickname data was malformed " , e ) ;
2023-01-18 16:29:58 -05:00
2023-06-25 21:07:27 -04:00
} catch ( Exception e ) {
2023-01-18 16:29:58 -05:00
ctx . status ( 500 ) ;
2023-06-25 21:07:27 -04:00
ctx . result ( " An error occurred while changing the camera's nickname " ) ;
logger . error ( " An error occurred while changing the camera's nickname " , e ) ;
2023-01-18 16:29:58 -05:00
}
}
2023-06-25 21:07:27 -04:00
public static void onMetricsPublishRequest ( Context ctx ) {
HardwareManager . getInstance ( ) . publishMetrics ( ) ;
ctx . status ( 204 ) ;
2020-10-16 16:48:24 -07:00
}
2024-02-01 21:42:54 -05:00
public static void onCalibrationSnapshotRequest ( Context ctx ) {
logger . info ( ctx . queryString ( ) . toString ( ) ) ;
2025-01-03 18:50:25 -05:00
String cameraUniqueName = ctx . queryParam ( " cameraUniqueName " ) ;
2024-02-01 21:42:54 -05:00
var width = Integer . parseInt ( ctx . queryParam ( " width " ) ) ;
var height = Integer . parseInt ( ctx . queryParam ( " height " ) ) ;
var observationIdx = Integer . parseInt ( ctx . queryParam ( " snapshotIdx " ) ) ;
CameraCalibrationCoefficients calList =
2025-01-01 03:04:20 -05:00
VisionSourceManager . getInstance ( )
. vmm
2025-01-03 18:50:25 -05:00
. getModule ( cameraUniqueName )
2024-02-01 21:42:54 -05:00
. getStateAsCameraConfig ( )
. calibrations
. stream ( )
. filter (
it - >
2024-10-19 01:23:23 -04:00
Math . abs ( it . unrotatedImageSize . width - width ) < 1e - 4
& & Math . abs ( it . unrotatedImageSize . height - height ) < 1e - 4 )
2024-02-01 21:42:54 -05:00
. findFirst ( )
. orElse ( null ) ;
if ( calList = = null | | calList . observations . size ( ) < observationIdx ) {
ctx . status ( 404 ) ;
return ;
}
// encode as jpeg to save even more space. reduces size of a 1280p image from 300k to 25k
var jpegBytes = new MatOfByte ( ) ;
2024-10-13 01:29:17 -04:00
Mat img = null ;
try {
img =
Imgcodecs . imread (
calList . observations . get ( observationIdx ) . snapshotDataLocation . toString ( ) ) ;
} catch ( Exception e ) {
ctx . status ( 500 ) ;
ctx . result ( " Unable to read calibration image " ) ;
return ;
}
if ( img = = null | | img . empty ( ) ) {
ctx . status ( 500 ) ;
ctx . result ( " Unable to read calibration image " ) ;
return ;
}
Imgcodecs . imencode ( " .jpg " , img , jpegBytes , new MatOfInt ( Imgcodecs . IMWRITE_JPEG_QUALITY , 60 ) ) ;
2024-02-01 21:42:54 -05:00
ctx . result ( jpegBytes . toArray ( ) ) ;
jpegBytes . release ( ) ;
ctx . status ( 200 ) ;
}
public static void onCalibrationExportRequest ( Context ctx ) {
logger . info ( ctx . queryString ( ) . toString ( ) ) ;
2025-01-03 18:50:25 -05:00
String cameraUniqueName = ctx . queryParam ( " cameraUniqueName " ) ;
2024-02-01 21:42:54 -05:00
var width = Integer . parseInt ( ctx . queryParam ( " width " ) ) ;
var height = Integer . parseInt ( ctx . queryParam ( " height " ) ) ;
2025-01-03 18:50:25 -05:00
var cc =
VisionSourceManager . getInstance ( ) . vmm . getModule ( cameraUniqueName ) . getStateAsCameraConfig ( ) ;
2024-02-01 21:42:54 -05:00
CameraCalibrationCoefficients calList =
cc . calibrations . stream ( )
. filter (
it - >
2024-10-19 01:23:23 -04:00
Math . abs ( it . unrotatedImageSize . width - width ) < 1e - 4
& & Math . abs ( it . unrotatedImageSize . height - height ) < 1e - 4 )
2024-02-01 21:42:54 -05:00
. findFirst ( )
. orElse ( null ) ;
if ( calList = = null ) {
ctx . status ( 404 ) ;
return ;
}
var filename = " photon_calibration_ " + cc . uniqueName + " _ " + width + " x " + height + " .json " ;
ctx . contentType ( " application/zip " ) ;
ctx . header ( " Content-Disposition " , " attachment; filename= \" " + filename + " \" " ) ;
ctx . json ( calList ) ;
ctx . status ( 200 ) ;
}
2023-11-05 11:33:45 -05:00
public static void onImageSnapshotsRequest ( Context ctx ) {
var snapshots = new ArrayList < HashMap < String , Object > > ( ) ;
var cameraDirs = ConfigManager . getInstance ( ) . getImageSavePath ( ) . toFile ( ) . listFiles ( ) ;
if ( cameraDirs ! = null ) {
try {
for ( File cameraDir : cameraDirs ) {
var cameraSnapshots = cameraDir . listFiles ( ) ;
if ( cameraSnapshots = = null ) continue ;
String cameraUniqueName = cameraDir . getName ( ) ;
for ( File snapshot : cameraSnapshots ) {
var snapshotData = new HashMap < String , Object > ( ) ;
var bufferedImage = ImageIO . read ( snapshot ) ;
var buffer = new ByteArrayOutputStream ( ) ;
ImageIO . write ( bufferedImage , " jpg " , buffer ) ;
byte [ ] data = buffer . toByteArray ( ) ;
snapshotData . put ( " snapshotName " , snapshot . getName ( ) ) ;
snapshotData . put ( " cameraUniqueName " , cameraUniqueName ) ;
snapshotData . put ( " snapshotData " , data ) ;
snapshots . add ( snapshotData ) ;
}
}
} catch ( IOException e ) {
ctx . status ( 500 ) ;
ctx . result ( " Unable to read saved images " ) ;
}
}
ctx . status ( 200 ) ;
ctx . json ( snapshots ) ;
}
2024-01-03 14:32:04 -07:00
public static void onCameraCalibImagesRequest ( Context ctx ) {
try {
HashMap < String , HashMap < String , ArrayList < HashMap < String , Object > > > > snapshots =
new HashMap < > ( ) ;
var cameraDirs = ConfigManager . getInstance ( ) . getCalibDir ( ) . toFile ( ) . listFiles ( ) ;
if ( cameraDirs ! = null ) {
var camData = new HashMap < String , ArrayList < HashMap < String , Object > > > ( ) ;
for ( var cameraDir : cameraDirs ) {
var resolutionDirs = cameraDir . listFiles ( ) ;
if ( resolutionDirs = = null ) continue ;
for ( var resolutionDir : resolutionDirs ) {
var calibImages = resolutionDir . listFiles ( ) ;
if ( calibImages = = null ) continue ;
var resolutionImages = new ArrayList < HashMap < String , Object > > ( ) ;
for ( var calibImg : calibImages ) {
var snapshotData = new HashMap < String , Object > ( ) ;
var bufferedImage = ImageIO . read ( calibImg ) ;
var buffer = new ByteArrayOutputStream ( ) ;
ImageIO . write ( bufferedImage , " png " , buffer ) ;
byte [ ] data = buffer . toByteArray ( ) ;
snapshotData . put ( " snapshotData " , data ) ;
snapshotData . put ( " snapshotFilename " , calibImg . getName ( ) ) ;
resolutionImages . add ( snapshotData ) ;
}
camData . put ( resolutionDir . getName ( ) , resolutionImages ) ;
}
var cameraName = cameraDir . getName ( ) ;
snapshots . put ( cameraName , camData ) ;
}
}
ctx . json ( snapshots ) ;
} catch ( Exception e ) {
ctx . status ( 500 ) ;
ctx . result ( " An error occurred while getting calib data " ) ;
logger . error ( " An error occurred while getting calib data " , e ) ;
}
}
2023-06-25 21:07:27 -04:00
/ * *
* Create a temporary file using the UploadedFile from Javalin .
*
* @param file the uploaded file .
* @return Temporary file . Empty if the temporary file was unable to be created .
* /
private static Optional < File > handleTempFileCreation ( UploadedFile file ) {
var tempFilePath =
2023-10-05 18:22:56 -04:00
new File ( Path . of ( System . getProperty ( " java.io.tmpdir " ) , file . filename ( ) ) . toString ( ) ) ;
boolean makeDirsRes = tempFilePath . getParentFile ( ) . mkdirs ( ) ;
2023-10-17 16:23:05 -04:00
if ( ! makeDirsRes & & ! ( tempFilePath . getParentFile ( ) . exists ( ) ) ) {
2023-10-05 18:22:56 -04:00
logger . error (
2023-10-17 16:23:05 -04:00
" There was an error while creating "
+ tempFilePath . getAbsolutePath ( )
+ " ! Exists: "
+ tempFilePath . getParentFile ( ) . exists ( ) ) ;
2023-10-05 18:22:56 -04:00
return Optional . empty ( ) ;
}
2023-06-25 21:07:27 -04:00
2020-08-26 10:03:56 -07:00
try {
2023-10-05 18:22:56 -04:00
FileUtils . copyInputStreamToFile ( file . content ( ) , tempFilePath ) ;
2023-06-25 21:07:27 -04:00
} catch ( IOException e ) {
logger . error (
2023-10-17 16:23:05 -04:00
" There was an error while copying "
+ file . filename ( )
+ " to the temp file "
+ tempFilePath . getAbsolutePath ( ) ) ;
2023-06-25 21:07:27 -04:00
return Optional . empty ( ) ;
2020-08-26 10:03:56 -07:00
}
2023-06-25 21:07:27 -04:00
return Optional . of ( tempFilePath ) ;
2020-08-26 10:03:56 -07:00
}
2023-06-25 21:07:27 -04:00
/ * *
* Restart the running program . Note that this doesn ' t actually restart the program itself ,
* instead , it relies on systemd or an equivalent .
* /
private static void restartProgram ( ) {
TimedTaskManager . getInstance ( )
. addOneShotTask (
( ) - > {
if ( Platform . isLinux ( ) ) {
try {
new ShellExec ( ) . executeBashCommand ( " systemctl restart photonvision.service " ) ;
} catch ( IOException e ) {
logger . error ( " Could not restart device! " , e ) ;
System . exit ( 0 ) ;
}
} else {
System . exit ( 0 ) ;
}
} ,
0 ) ;
2020-08-26 10:03:56 -07:00
}
2024-10-24 20:48:02 -07:00
public static void onNukeConfigDirectory ( Context ctx ) {
ConfigManager . getInstance ( ) . setWriteTaskEnabled ( false ) ;
ConfigManager . getInstance ( ) . disableFlushOnShutdown ( ) ;
Logger . closeAllLoggers ( ) ;
if ( ConfigManager . nukeConfigDirectory ( ) ) {
ctx . status ( 200 ) ;
ctx . result ( " Successfully nuked config dir " ) ;
restartProgram ( ) ;
} else {
ctx . status ( 500 ) ;
ctx . result ( " There was an error while nuking the config directory " ) ;
}
}
public static void onNukeOneCamera ( Context ctx ) {
try {
var payload = kObjectMapper . readTree ( ctx . bodyInputStream ( ) ) ;
var name = payload . get ( " cameraUniqueName " ) . asText ( ) ;
logger . warn ( " Deleting camera name " + name ) ;
var cameraDir = ConfigManager . getInstance ( ) . getCalibrationImageSavePath ( name ) . toFile ( ) ;
if ( cameraDir . exists ( ) ) {
FileUtils . deleteDirectory ( cameraDir ) ;
}
2025-01-01 03:04:20 -05:00
VisionSourceManager . getInstance ( ) . deleteVisionSource ( name ) ;
2024-10-24 20:48:02 -07:00
ctx . status ( 200 ) ;
} catch ( IOException e ) {
// todo
logger . error ( " asdf " , e ) ;
ctx . status ( 500 ) ;
}
}
2025-01-01 03:04:20 -05:00
public static void onActivateMatchedCameraRequest ( Context ctx ) {
logger . info ( ctx . queryString ( ) . toString ( ) ) ;
2025-01-03 18:50:25 -05:00
String cameraUniqueName = ctx . queryParam ( " cameraUniqueName " ) ;
2025-01-01 03:04:20 -05:00
2025-01-03 18:50:25 -05:00
if ( VisionSourceManager . getInstance ( ) . reactivateDisabledCameraConfig ( cameraUniqueName ) ) {
2025-01-01 03:04:20 -05:00
ctx . status ( 200 ) ;
} else {
ctx . status ( 403 ) ;
}
2025-01-03 18:50:25 -05:00
ctx . result ( " Successfully assigned camera with unique name: " + cameraUniqueName ) ;
2025-01-01 03:04:20 -05:00
}
public static void onAssignUnmatchedCameraRequest ( Context ctx ) {
logger . info ( ctx . queryString ( ) . toString ( ) ) ;
PVCameraInfo camera ;
try {
camera = JacksonUtils . deserialize ( ctx . queryParam ( " cameraInfo " ) , PVCameraInfo . class ) ;
} catch ( IOException e ) {
ctx . status ( 401 ) ;
return ;
}
if ( VisionSourceManager . getInstance ( ) . assignUnmatchedCamera ( camera ) ) {
ctx . status ( 200 ) ;
} else {
2025-01-03 18:50:25 -05:00
ctx . status ( 404 ) ;
2025-01-01 03:04:20 -05:00
}
ctx . result ( " Successfully assigned camera: " + camera ) ;
}
public static void onUnassignCameraRequest ( Context ctx ) {
logger . info ( ctx . queryString ( ) . toString ( ) ) ;
2025-01-03 18:50:25 -05:00
String cameraUniqueName = ctx . queryParam ( " cameraUniqueName " ) ;
2025-01-01 03:04:20 -05:00
2025-01-03 18:50:25 -05:00
if ( VisionSourceManager . getInstance ( ) . deactivateVisionSource ( cameraUniqueName ) ) {
2025-01-01 03:04:20 -05:00
ctx . status ( 200 ) ;
} else {
ctx . status ( 403 ) ;
}
ctx . status ( 200 ) ;
2025-01-03 18:50:25 -05:00
ctx . result ( " Successfully assigned camera with unique name: " + cameraUniqueName ) ;
2025-01-01 03:04:20 -05:00
}
2020-06-27 14:58:03 -07:00
}