Skip to content
This repository was archived by the owner on Sep 6, 2024. It is now read-only.

Commit

Permalink
#66, #61, #62
Browse files Browse the repository at this point in the history
  • Loading branch information
rgatkinson committed Nov 24, 2015
1 parent 5f38259 commit 8bd4f07
Show file tree
Hide file tree
Showing 6 changed files with 9 additions and 61 deletions.
Binary file modified FtcRobotController/libs/FtcCommon-release.aar
Binary file not shown.
Binary file modified FtcRobotController/libs/Hardware-release.aar
Binary file not shown.
Binary file modified FtcRobotController/libs/RobotCore-release.aar
Binary file not shown.
Original file line number Diff line number Diff line change
Expand Up @@ -178,7 +178,7 @@ else if (lhs.isAnnotationPresent(Autonomous.class) && rhs.isAnnotationPresent(Au
if (nameBuilder.length() > 0) nameBuilder.append(com.qualcomm.robotcore.util.Util.ASCII_RECORD_SEPARATOR);
nameBuilder.append(getOpModeName(opMode));
}
if (TypeConversion.stringToUtf8(nameBuilder.toString()).length >= Command.MAX_COMMAND_LENGTH) // see Command.Command
if (TypeConversion.stringToUtf8(nameBuilder.toString()).length > Command.MAX_COMMAND_LENGTH) // see Command.Command
{
reportOpModeConfigurationError("OpMode names are too long to be sent to the Driver Station");
this.opModeManager.register("OpMode names too long", OpModeNamesTooLong.class);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,11 +50,6 @@ public EasyModernController(OpMode context, ModernRoboticsUsbDevice target, Read
// We *have to* give a live ReadWriteRunnable to our parent constructor, so we grudgingly do so
super(target.getSerialNumber(), SwerveThreadContext.getEventLoopManager(), readWriteRunnable);

// Wait until the thing actually gets going. We need it to get to the point where the
// 'this.running=true' has at least been set so that the 'this.running=false' we are
// about to do in the close() in next line down will sequence correctly against it.
readWriteRunnable.waitUntilRunGetsGoing();

// Then shut it down right away, because we want to start disarmed until we fully configure
closeModernRoboticsUsbDevice(this);

Expand All @@ -64,9 +59,9 @@ public EasyModernController(OpMode context, ModernRoboticsUsbDevice target, Read
this.isArmed = false;
this.writeStatus = WRITE_STATUS.IDLE;

ReadWriteRunnableStandard readWriteRunnableStandard = MemberUtil.getReadWriteRunnableModernRoboticsUsbDevice(target);
ReadWriteRunnableUsbHandler handler = MemberUtil.getHandlerOfReadWriteRunnableStandard(readWriteRunnableStandard);
this.robotUsbDevice = MemberUtil.getRobotUsbDeviceOfReadWriteRunnableUsbHandler(handler);
ReadWriteRunnableStandard targetReadWriteRunnable = (ReadWriteRunnableStandard)MemberUtil.getReadWriteRunnableModernRoboticsUsbDevice(target);
ReadWriteRunnableUsbHandler targetHandler = MemberUtil.getHandlerOfReadWriteRunnableStandard(targetReadWriteRunnable);
this.robotUsbDevice = MemberUtil.getRobotUsbDeviceOfReadWriteRunnableUsbHandler(targetHandler);
}

//----------------------------------------------------------------------------------------------
Expand All @@ -87,7 +82,7 @@ static void closeModernRoboticsUsbDevice(ModernRoboticsUsbDevice usbDevice)
{
// Get access to the state
ExecutorService service = MemberUtil.getExecutorServiceModernRoboticsUsbDevice(usbDevice);
ReadWriteRunnableStandard readWriteRunnableStandard = MemberUtil.getReadWriteRunnableModernRoboticsUsbDevice(usbDevice);
ReadWriteRunnableStandard readWriteRunnableStandard = (ReadWriteRunnableStandard)MemberUtil.getReadWriteRunnableModernRoboticsUsbDevice(usbDevice);

// Stop accepting new work
service.shutdown();
Expand All @@ -99,9 +94,6 @@ static void closeModernRoboticsUsbDevice(ModernRoboticsUsbDevice usbDevice)
ReadWriteRunnableUsbHandler dummyHandler = new ReadWriteRunnableUsbHandler(robotUsbDevice);
MemberUtil.setHandlerOfReadWriteRunnableStandard(readWriteRunnableStandard, dummyHandler);

// Set 'running' to false; this fixes a race condition
MemberUtil.setRunningReadWriteRunnableStandard(readWriteRunnableStandard, false);

// Ok: actually carry out the close
readWriteRunnableStandard.close();

Expand Down Expand Up @@ -272,42 +264,6 @@ static class DummyRobotUsbDevice implements RobotUsbDevice
}
}

/**
* A handler that let's you know when it's had methods called on it
*/
static class InterlockingReadWriteRunnableUsbHandler extends ReadWriteRunnableUsbHandler
{
private ManualResetEvent methodCalled = new ManualResetEvent(false);

public InterlockingReadWriteRunnableUsbHandler(RobotUsbDevice device)
{
super(device);
}

@Override public void purge(RobotUsbDevice.Channel channel) throws RobotCoreException
{
methodCalled.set();
super.purge(channel);
}

@Override public void read(int address, byte[] buffer) throws RobotCoreException, InterruptedException
{
methodCalled.set();
super.read(address, buffer);
}

@Override public void write(int address, byte[] buffer) throws RobotCoreException, InterruptedException
{
methodCalled.set();
super.write(address, buffer);
}

void awaitMethodCall() throws InterruptedException
{
this.methodCalled.waitOne();
}
}

/**
* This class is a ReadWriteRunnableStandard but one that doesn't report any errors
* due to connection failures in its blockUntilReady(). And you can interlock with its
Expand All @@ -318,14 +274,6 @@ static class ReadWriteRunnableHandy extends ReadWriteRunnableStandard
public ReadWriteRunnableHandy(SerialNumber serialNumber, RobotUsbDevice device, int monitorLength, int startAddress, boolean debug)
{
super(serialNumber, device, monitorLength, startAddress, debug);
InterlockingReadWriteRunnableUsbHandler handler = new InterlockingReadWriteRunnableUsbHandler(device);
MemberUtil.setHandlerOfReadWriteRunnableStandard(this, handler);
}

void waitUntilRunGetsGoing() throws InterruptedException
// We ideally want to wait until after 'running' is set and the log is written
{
((InterlockingReadWriteRunnableUsbHandler)this.usbHandler).awaitMethodCall();
}

@Override public void run()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,11 +22,11 @@ public class MemberUtil

public static ReadWriteRunnableUsbHandler getHandlerOfReadWriteRunnableStandard(ReadWriteRunnableStandard readWriteRunnableStandard)
{
return Util.<ReadWriteRunnableUsbHandler>getPrivateObjectField(readWriteRunnableStandard, 13);
return Util.<ReadWriteRunnableUsbHandler>getPrivateObjectField(readWriteRunnableStandard, 14);
}
public static void setHandlerOfReadWriteRunnableStandard(ReadWriteRunnableStandard readWriteRunnableStandard, ReadWriteRunnableUsbHandler handler)
{
Util.setPrivateObjectField(readWriteRunnableStandard, 13, handler);
Util.setPrivateObjectField(readWriteRunnableStandard, 14, handler);
}

public static void setRunningReadWriteRunnableStandard(ReadWriteRunnableStandard readWriteRunnableStandard, boolean isRunning)
Expand All @@ -47,12 +47,12 @@ public static RobotUsbDevice getRobotUsbDeviceOfReadWriteRunnableUsbHandler(Read
// ModernRoboticsUsbDevice
//----------------------------------------------------------------------------------------------

public static ReadWriteRunnableStandard getReadWriteRunnableModernRoboticsUsbDevice(ModernRoboticsUsbDevice device)
public static ReadWriteRunnable getReadWriteRunnableModernRoboticsUsbDevice(ModernRoboticsUsbDevice device)
// Here we rely on the fact that ReadWriteRunnableBlocking inherits from ReadWriteRunnableStandard
{
return Util.<ReadWriteRunnableStandard>getPrivateObjectField(device, 0);
}
public static void setReadWriteRunnableModernRoboticsUsbDevice(ModernRoboticsUsbDevice device, ReadWriteRunnableStandard readWriteRunnableStandard)
public static void setReadWriteRunnableModernRoboticsUsbDevice(ModernRoboticsUsbDevice device, ReadWriteRunnable readWriteRunnableStandard)
{
Util.setPrivateObjectField(device, 0, readWriteRunnableStandard);
}
Expand Down

0 comments on commit 8bd4f07

Please sign in to comment.