Sample APK

Movement and Rotation of Astrobee aboard Kibo quaternion

YourService.java Sample Code


package jp.jaxa.iss.kibo.rpc.sampleapk;
 
import jp.jaxa.iss.kibo.rpc.api.KiboRpcService;
 
import gov.nasa.arc.astrobee.types.Point;
import gov.nasa.arc.astrobee.types.Quaternion;
 
import org.opencv.core.Mat;
 
/**
 * Class meant to handle commands from the Ground Data System and execute them in Astrobee.
 */
 
public class YourService extends KiboRpcService {
    @Override
    protected void runPlan1(){
        // The mission starts- starts timer, returns Success/Failure
        api.startMission();
 
        // Move to a point.
        Point point = new Point(10.9d, -9.92284d, 5.195d);
        Quaternion quaternion = new Quaternion(0f, 0f, -0.707f, 0.707f);
        api.moveTo(point, quaternion, false);
 
        // Get a camera image.
        Mat image = api.getMatNavCam();
 
        /* *********************************************************************** */
        /* Write your code to recognize type and number of items in the each area! */
        /* *********************************************************************** */
 
        // When you recognize items, let’s set the type and number.
        api.setAreaInfo(1, "item_name", 1);
 
        /* **************************************************** */
        /* Let's move to the each area and recognize the items. */
        /* **************************************************** */
 
        // When you move to the front of the astronaut, report the rounding completion.
        api.reportRoundingCompletion();
 
        /* ********************************************************** */
        /* Write your code to recognize which item the astronaut has. */
        /* ********************************************************** */
 
        // Let's notify the astronaut when you recognize it.
        api.notifyRecognitionItem();
 
        /* ******************************************************************************************************* */
        /* Write your code to move Astrobee to the location of the target item (what the astronaut is looking for) */
        /* ******************************************************************************************************* */
 
        // Take a snapshot of the target item.
        api.takeTargetItemSnapshot();
    }
 
    @Override
    protected void runPlan2(){
       // write your plan 2 here.
    }
 
    @Override
    protected void runPlan3(){
        // write your plan 3 here.
    }
 
    // You can add your method.
    private String yourMethod(){
        return "your method";
    }
}

Game API Overview


See Game API details in the KiboRPC Programming Manual for full API

MethodDescription
api.startMission()starts timer; returns boolean result (Success/Failure)
ex) boolean result = api.startMission();
api.laserControl()Astrobee shoots a laser
ex) Result result = api.laserControl(true);
api.moveTo()Executes Astrobee’s movement and rotation (both in absolute values)
point: specifies movement coordinates
quaternion: specifies rotation in quaternions
api.reportPoint1Arrival()Call this function when you want to declare Astrobee’s arrival at Point1
api.getMatNavCam()Uses a NavCam to shoot images
Will need image processing (e.g., OpenCV ArUco) to recognize AR tags
api.takeTargetItemSnapshotRetrieves snapshot of Target1 to determine where Target1 was hit by the laser
api.reportMissionCompletionSend mission completion communication to astronauts
In on-orbit final round, it plays the prepared audio data

Improving Sample APK


Logs


  • records the status of Astrobee
  • Helps visualize program execution (like unexpected movements, robot position)
public class YourService extends KiboRpcService {
 
    private final String TAG = this.getClass().getSimpleName();
 
    @Override
    protected void runPlan1(){
        // The mission starts- starts timer, returns Success/Failure
        api.startMission();
        Log.i(TAG, "Start mission");

Aiming for Point1


  • Revise api.moveTo() and avoid KOZ (Keep Out Zone)
    • Set initial point to Point1’s coordinates (10.71000, -7.7000, 4.48000), or whatever’s in the rulebook
//Movetoapoint.
//Pointpoint=newPoint(10.9d,-9.92284d,5.195d);
Pointpoint=newPoint(10.71000f,-7.70000f,4.48000f);
  • Rotate to face towards Target1 from the starting point
//Quaternionquaternion=newQuaternion(0f,0f,-0.707f,0.707f);
Quaternionquaternion=newQuaternion(0f,0.707f,0f,0.707f);
  • An example of a disturbance-resistance program can be found in the programming manual
// api.moveTo(point, quaternion, false);
Result result = api.moveTo(point, quaternion, true);
 
// Check result and loop while moveTo api has not succeeded
final int LOOP_MAX = 5;
int loopCounter = 0;
while (!result.hasSucceeded() && loopCounter < LOOP_MAX) {
    // Retry
    result = api.moveTo(point, quaternion, true);
    ++loopCounter;
}

Simulation Results


  • Analyze your program though simulation videos, logs, and camera images

  • Saving NavCam Images

    • Refer to programming manual for which type of images are used to recognize AR tags
//Getacameraimage.
Matimage=api.getMatNavCam();
 
//Savetheimage
api.saveMatImage(image,"file_name.png");
  • Check simulation results
    • Upload app-debug.apk with optional memo (e.g. “change moveTo() parameters to rulebook values and add saveMatImage()“)

  • Check log and images from NavCam
    • Click “DOWNLOAD LOG FILES”
      • Open app-debug.apk_results/adb.log
      • Look for “I/YourService” logs

  • Click “DOWNLOAD LOG FILES”
    • Open app-debug.apk_results/DebugImages

Conditionals and Exceptions


  • The target changes depending on other elements like time
    • if misjudge the target or timing, ammonia may fill up the KIBO and endanger the astronauts

Find Suitable Target for Situation


  • getActiveTarget()
    • function for Astrobee to check the situation (e.g. may return a leaking target number)
    • Use within if block to change movement depending on conditions (e.g. your own coords, KOZ coords, remaining time etc.)
@Override
protected void runPlan1(){
    // The mission starts- starts timer, returns Success/Failure
    api.startMission();
    Log.i(TAG, "Start mission");
 
    // Get active target id list
    List<Integer> list = api.getActiveTargets();
 
    if (list.get(0) == 1) {
        Point point = new Point(11.143d, -6.76067d, 4.9654d);
        Quaternion quaternion = new Quaternion(0f, 0f, -0.707f, 0.707f);
        api.moveTo(point, quaternion, false);
    }

Exception Handling


Implement exception handling to make Astrobee move safely in unexpected situtations

// Get a camera image.
Mat image = api.getMatNavCam();
 
try {
    String imgStr = yourMethod();
    Log.i(TAG, "If yourMethod() throws Exception, this step is not executed");
} catch (Exception e) {
    Log.i(TAG, "If yourMethod() throws Exception, this step is executed");
}

NullPointException


  • Example: NullPointException will be thrown if you try to analyze an image while image is NULL
    • How to handle:
if (image == null) {
    // Error handling
} else {
    String imageStr = yourMethod(image);
}

IndexOutOfBoundsException


  • Example: if getActiveTargets() returns an empty list, trying to call list.get(0) will throw an IndexOutOfBoundsException
    • How to handle:
// Get active target id list
List<Integer> list = api.getActiveTargets();
 
for (int i = 0; i < list.size(); i++) {
    if (list.get(i) == 1) {
        Point point = new Point(11.143d, -6.76067d, 4.9654d);
        Quaternion quaternion = new Quaternion(0f, 0f, -0.707f, 0.707f);
        api.moveTo(point, quaternion, false);
    }
}

Next- quaternion