Skip to content

Commit

Permalink
Merge pull request #120 from DeepBlueRobotics/complete-workaround-for…
Browse files Browse the repository at this point in the history
…-HALSimWS-SimDevice-deadlocks

Complete-workaround-for-HALSimWS-SimDevice-deadlocks
  • Loading branch information
brettle authored Jul 19, 2024
2 parents 7500719 + 69de227 commit 449abc6
Show file tree
Hide file tree
Showing 10 changed files with 270 additions and 145 deletions.
21 changes: 17 additions & 4 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -32,11 +32,24 @@ advantage of the WPILib's WebSockets server desktop simulation extension.
### Demo

1. In VSCode run the `WPILib: Create a new project` command and create the example project.
1. Add the DeepBlueSim Gradle plugin to the `build.gradle` as described above.
1. In VSCode run the `WPILib: Simulate Robot Code on Desktop` command and select both
2. Add the DeepBlueSim Gradle plugin to the `build.gradle` as described above.
3. If you are not using [`lib199`](https://github.com/DeepBlueRobotics/lib199), add the following 2
lines to your robot's `simulationInit()` method (`lib199` handles this automatically):
```java
@Override
public void simulationInit() {
// Regularly request a HALSimWS connection from the DeepBlueSim controller (if/when it is
// listening). To workaround https://github.com/wpilibsuite/allwpilib/issues/6842, this must
// be done *after* any SimDevices have been created.
var reqPublisher = NetworkTableInstance.getDefault()
.getStringTopic("/DeepBlueSim/Coordinator/request").publish();
addPeriodic(() -> reqPublisher.set("connectHALSimWS"), kDefaultPeriod);
}
```
4. In VSCode run the `WPILib: Simulate Robot Code on Desktop` command and select both
`libhalsim_gui` and `libhalsim_ws_server` as the extensions to use.
1. Start Webots and open *your_example_project*`/Webots/worlds/DBSExample.wbt`
1. In the HALSim GUI, select `Autonomous` to see the robot drive forward for 2 seconds, or
5. Start Webots and open *your_example_project*`/Webots/worlds/DBSExample.wbt`
6. In the HALSim GUI, select `Autonomous` to see the robot drive forward for 2 seconds, or
select `Teleop` and use the keyboard on joystick to drive the robot around.

## Details
Expand Down
2 changes: 1 addition & 1 deletion example/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ plugins {
id "java"
id 'jvm-test-suite'
id "edu.wpi.first.GradleRIO" version "2024.3.1"
id "org.carlmontrobotics.deepbluesim" version "2024.0.0"
id "org.carlmontrobotics.deepbluesim" version "unspecified"
}

java {
Expand Down
23 changes: 20 additions & 3 deletions example/src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,11 @@

package frc.robot;

import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.StadiaController.Axis;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.PWMVictorSPX;
import edu.wpi.first.wpilibj.motorcontrol.PWMMotorController;
Expand All @@ -22,7 +24,7 @@
*/
public class Robot extends TimedRobot {

private final Joystick m_stick = new Joystick(0);
private final GenericHID m_controller = new GenericHID(0);
private final Timer m_timer = new Timer();
private DifferentialDrive m_robotDrive;
private PWMMotorController m_leftMaster;
Expand Down Expand Up @@ -51,6 +53,19 @@ public void robotInit() {
m_elevator = new PWMVictorSPX(4);
}

/**
* This function is run when the robot is first started up in simulation.
*/
@Override
public void simulationInit() {
// Regularly request a HALSimWS connection from the DeepBlueSim controller (if/when it is
// listening). To workaround https://github.com/wpilibsuite/allwpilib/issues/6842, this must
// be done *after* any SimDevices have been created.
var reqPublisher = NetworkTableInstance.getDefault()
.getStringTopic("/DeepBlueSim/Coordinator/request").publish();
addPeriodic(() -> reqPublisher.set("connectHALSimWS"), kDefaultPeriod);
}

public void close() {
System.out.println("Closing motors in Robot.close()");
m_leftMaster.close();
Expand Down Expand Up @@ -94,7 +109,9 @@ public void teleopInit() {}
*/
@Override
public void teleopPeriodic() {
m_robotDrive.arcadeDrive(m_stick.getY(), m_stick.getX());
m_robotDrive.arcadeDrive(-m_controller.getRawAxis(Axis.kLeftY.value),
m_controller.getRawAxis(Axis.kLeftX.value));
m_elevator.set(-m_controller.getRawAxis(Axis.kRightY.value));
}

/**
Expand Down
20 changes: 1 addition & 19 deletions plugin/controller/src/main/java/DeepBlueSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@
import org.carlmontrobotics.deepbluesim.Simulation;
import org.carlmontrobotics.deepbluesim.WebotsSupervisor;
import org.carlmontrobotics.wpiws.connection.RunningObject;
import org.carlmontrobotics.wpiws.connection.WSConnection;

// NOTE: Webots expects the controller class to *not* be in a package and have a name that matches
// the name of the jar.
Expand All @@ -34,8 +33,6 @@ public class DeepBlueSim {
// Webots/controllers/DeepBlueSim/logging.properties file so that ".level=FINE".
private static Logger LOG = null;

private static RunningObject<WebSocketClient> wsConnection = null;

private static void startNetworkTablesClient(NetworkTableInstance inst) {
inst.startClient4("Webots controller");
inst.setServer("localhost");
Expand Down Expand Up @@ -97,12 +94,7 @@ public void uncaughtException(Thread arg0, Throwable t) {
}

if (connectToRobotCode) {
WebotsSupervisor.init(robot, basicTimeStep, () -> {
if (wsConnection == null)
return null;
else
return wsConnection.object;
});
WebotsSupervisor.init(robot, basicTimeStep);
}

// Wait until startup has completed to ensure that the Webots simulator is
Expand All @@ -119,16 +111,6 @@ public void uncaughtException(Thread arg0, Throwable t) {
// user does.
robot.simulationSetMode(Supervisor.SIMULATION_MODE_PAUSE);

// Connect to the robot code on a separate thread. Does not block.
try {
wsConnection = WSConnection.connectHALSim(true);
} catch (URISyntaxException e) {
LOG.log(Level.ERROR,
"Error occurred connecting to server:", e);
System.exit(1);
return;
}

Runtime.getRuntime().addShutdownHook(new Thread(() -> {
// If connections haven't already been closed, we try to close them now. Note that
// this might silently fail if it takes too long.
Expand Down
Loading

0 comments on commit 449abc6

Please sign in to comment.