001/* 002 * Copyright (C) Cross The Road Electronics. All rights reserved. 003 * License information can be found in CTRE_LICENSE.txt 004 * For support and suggestions contact support@ctr-electronics.com or file 005 * an issue tracker at https://github.com/CrossTheRoadElec/Phoenix-Releases 006 */ 007package com.ctre.phoenix6; 008 009import java.util.Collection; 010 011import com.ctre.phoenix6.configs.AudioConfigs; 012import com.ctre.phoenix6.hardware.traits.CommonDevice; 013import com.ctre.phoenix6.jni.OrchestraJNI; 014 015/** 016 * Orchestra is used to play music through devices. It uses a "Chirp" (.chrp) music 017 * file that can be generated using Phoenix Tuner. Chirp files are generated from 018 * standard MIDI files. 019 * <p> 020 * Any Chirp file located in the src/main/deploy directory of your FRC project will 021 * automatically be copied to the roboRIO on code deploy. 022 * <p> 023 * Unless {@link AudioConfigs#AllowMusicDurDisable} is enabled, the robot must be 024 * enabled to play music. Additionally, devices playing in Orchestra will not 025 * run any other control requests while Orchestra is running. Users can 026 * {@link #pause} or {@link #stop} the Orchestra to re-enable device control. 027 * <p> 028 * Each device can only play a single track within the music file. For multi-track 029 * files, multiple devices are needed. Devices can be added with an explicit track 030 * number. Otherwise, the first track will be played through the first Talon FX added, 031 * the second track will be played through the second Talon FX added, etc. 032 * <p> 033 * To use Orchestra: 034 * <ul> 035 * <li> Add the Talon FXs to be used as instruments using {@link #addInstrument}. 036 * <li> Load the Chirp file to be played using {@link #loadMusic}. This can also 037 * be done in the Orchestra constructor. 038 * </ul> 039 * Both of these can also be done in the Orchestra constructor. 040 * <p> 041 * Once ready, the Orchestra can be controlled using {@link #play}/{@link #pause}/{@link #stop}. 042 * New music files can be loaded at any time. 043 */ 044public class Orchestra implements AutoCloseable { 045 private OrchestraJNI jni = new OrchestraJNI(); 046 047 /** 048 * Constructor for a new Orchestra. 049 */ 050 public Orchestra() { 051 jni.JNI_Create(); 052 } 053 054 /** 055 * Constructor for a new Orchestra using the given Chirp file. 056 * <p> 057 * This API is blocking on the file read. 058 * 059 * @param filepath The path to the music file to immediately load into the orchestra. 060 */ 061 public Orchestra(String filepath) { 062 this(); 063 loadMusic(filepath); 064 } 065 066 /** 067 * Constructor for a new Orchestra using the given instruments. 068 * 069 * @param instruments A collection of devices that will be used as instruments in the orchestra. 070 */ 071 public Orchestra(Collection<CommonDevice> instruments) { 072 this(); 073 for (var instrument : instruments) { 074 addInstrument(instrument); 075 } 076 } 077 078 /** 079 * Constructor for a new Orchestra using the given instruments and Chirp file. 080 * <p> 081 * This API is blocking on the file read. 082 * 083 * @param instruments A collection of devices that will be used as instruments in the orchestra. 084 * @param filepath The path to the music file to immediately load into the orchestra. 085 */ 086 public Orchestra(Collection<CommonDevice> instruments, String filepath) { 087 this(); 088 for (var instrument : instruments) { 089 addInstrument(instrument); 090 } 091 loadMusic(filepath); 092 } 093 094 /** 095 * Closes this Orchestra instance. 096 */ 097 @Override 098 public void close() { 099 jni.JNI_Close(); 100 } 101 102 /** 103 * Adds an instrument to the orchestra. 104 * <p> 105 * This adds the instrument to the next track; it does not wrap 106 * back to track 0 if all tracks have been filled. To assign 107 * multiple instruments to a track, use {@link #addInstrument(CommonDevice, int)}. 108 * 109 * @param instrument The device to add to the orchestra 110 * @return Status code of adding the device 111 */ 112 public final StatusCode addInstrument(CommonDevice instrument) { 113 return StatusCode.valueOf(jni.JNI_AddDevice(instrument.getNetwork().getName(), instrument.getDeviceHash())); 114 } 115 116 /** 117 * Adds an instrument to the orchestra on the given track. 118 * <p> 119 * This can be used to assign multiple instruments to a track. 120 * 121 * @param instrument The device to add to the orchestra 122 * @param trackNumber The track number the device should play, starting at 0 123 * @return Status code of adding the device 124 */ 125 public final StatusCode addInstrument(CommonDevice instrument, int trackNumber) { 126 return StatusCode.valueOf(jni.JNI_AddDeviceWithTrack(instrument.getNetwork().getName(), instrument.getDeviceHash(), trackNumber)); 127 } 128 129 /** 130 * Clears all instruments in the orchestra. 131 * 132 * @return Status code of clearing all devices 133 */ 134 public final StatusCode clearInstruments() { 135 return StatusCode.valueOf(jni.JNI_ClearDevices()); 136 } 137 138 /** 139 * Loads a Chirp file at the specified file path. 140 * <p> 141 * If the Chirp file is inside your "src/main/deploy" directory, it will be 142 * automatically deployed to a default directory on the roboRIO when you 143 * deploy code. For these files, the name and file extension is sufficient. 144 * <p> 145 * A Chirp file can be created from a MIDI file using Phoenix Tuner. 146 * <p> 147 * This API is blocking on the file read. 148 * 149 * @param filepath The path to the Chirp file 150 * @return Status code of loading the Chirp file 151 */ 152 public final StatusCode loadMusic(String filepath) { 153 return StatusCode.valueOf(jni.JNI_LoadMusic(filepath)); 154 } 155 156 /** 157 * Plays the loaded music file. If the player is paused, this will resume 158 * the orchestra. 159 * 160 * @return Status code of playing the orchestra 161 */ 162 public final StatusCode play() { 163 return StatusCode.valueOf(jni.JNI_Play()); 164 } 165 166 /** 167 * Pauses the loaded music file. This saves the current position in the 168 * track so it can be resumed later. 169 * 170 * @return Status code of pausing the orchestra 171 */ 172 public final StatusCode pause() { 173 return StatusCode.valueOf(jni.JNI_Pause()); 174 } 175 176 /** 177 * Stops the loaded music file. This resets the current position in the 178 * track to the start. 179 * 180 * @return Status code of stopping the orchestra 181 */ 182 public final StatusCode stop() { 183 return StatusCode.valueOf(jni.JNI_Stop()); 184 } 185 186 /** 187 * Gets whether the current track is actively playing. 188 * 189 * @return true if Orchestra is playing the music file 190 */ 191 public final boolean isPlaying() { 192 return jni.JNI_IsPlaying(); 193 } 194 195 /** 196 * Gets the current timestamp of the music file. The timestamp will reset 197 * to zero whenever {@link #loadMusic} or {@link #stop} is called. 198 * <p> 199 * If {@link #isPlaying} returns false, this method can be used to determine 200 * if the music is stopped or paused. 201 * 202 * @return The current timestamp of the music file, in seconds 203 */ 204 public final double getCurrentTime() { 205 return jni.JNI_GetCurrentTime(); 206 } 207}