// GUI void OnGUI() { GUIStyle myButtonStyle = new GUIStyle(GUI.skin.button); myButtonStyle.fontSize = 13; GUIStyle labelDetails = new GUIStyle(GUI.skin.GetStyle("label")); labelDetails.fontSize = 14; labelDetails.normal.textColor = Color.black; if (GUI.Button(new Rect(Screen.width - 170, 60, 150, 30), "IMU29 Heading Reset", myButtonStyle)) { print("Performing Heading Reset for IMU29"); ZenComponentHandle_t mComponent = new ZenComponentHandle_t(); OpenZen.ZenSensorComponentsByNumber(mZenHandle, mSensorHandle, OpenZen.g_zenSensorType_Imu, 0, mComponent); // perform heading reset OpenZen.ZenSensorComponentSetInt32Property(mZenHandle, mSensorHandle, mComponent, (int)EZenImuProperty.ZenImuProperty_OrientationOffsetMode, 1); } if (GUI.Button(new Rect(Screen.width - 170, 100, 150, 30), "IMU98 Heading Reset", myButtonStyle)) { print("Performing Heading Reset for IMU98"); ZenComponentHandle_t mComponent2 = new ZenComponentHandle_t(); OpenZen.ZenSensorComponentsByNumber(mZenHandle, mSensorHandle2, OpenZen.g_zenSensorType_Imu, 0, mComponent2); // perform heading reset OpenZen.ZenSensorComponentSetInt32Property(mZenHandle, mSensorHandle2, mComponent2, (int)EZenImuProperty.ZenImuProperty_OrientationOffsetMode, 1); } if (GUI.Button(new Rect(Screen.width - 170, 140, 150, 30), "IMUusb Heading Reset", myButtonStyle)) { print("Performing Heading Reset for IMUusb"); ZenComponentHandle_t mComponent3 = new ZenComponentHandle_t(); OpenZen.ZenSensorComponentsByNumber(mZenHandle, mSensorHandle3, OpenZen.g_zenSensorType_Imu, 0, mComponent3); // perform heading reset OpenZen.ZenSensorComponentSetInt32Property(mZenHandle, mSensorHandle3, mComponent3, (int)EZenImuProperty.ZenImuProperty_OrientationOffsetMode, 1); } //if (GUI.Button(new Rect(20, 20, 150, 30), "Calibrate Mousepad", myButtonStyle)) //{ // print("Record palm position"); // //} GUI.Label(new Rect(20, 20, 150, 50), "Timer: " + visualTime.ToString("f4") + " seconds.", labelDetails); }
// Start is called before the first frame update void Start() { // connection = new UdpConnection(); // connection.StartConnection(sendIp, sendPort, receivePort); Hand_demo.SetActive(!Hand_demo.activeSelf); initializeJoints(); // create OpenZen OpenZen.ZenInit(mZenHandle); // Hint: to get the io type and identifer for all connected sensor, // you cant start the DiscoverSensorScene. The information of all // found sensors is printed in the debug console of Unity after // the search is complete. // print("Trying to connect to OpenZen Sensor on IO " + OpenZenIoType + // " with sensor name " + OpenZenIdentifier); var sensorInitError = OpenZen.ZenObtainSensorByName(mZenHandle, OpenZenIoType, OpenZenIdentifier, 0, mSensorHandle); if (sensorInitError != ZenSensorInitError.ZenSensorInitError_None) { print("Error while connecting to sensor 29."); } else { ZenComponentHandle_t mComponent = new ZenComponentHandle_t(); OpenZen.ZenSensorComponentsByNumber(mZenHandle, mSensorHandle, OpenZen.g_zenSensorType_Imu, 0, mComponent); // enable sensor streaming, normally on by default anyways OpenZen.ZenSensorComponentSetBoolProperty(mZenHandle, mSensorHandle, mComponent, (int)EZenImuProperty.ZenImuProperty_StreamData, true); // set offset mode to heading OpenZen.ZenSensorComponentSetInt32Property(mZenHandle, mSensorHandle, mComponent, (int)EZenImuProperty.ZenImuProperty_OrientationOffsetMode, 1); // set the sampling rate to 100 Hz OpenZen.ZenSensorComponentSetInt32Property(mZenHandle, mSensorHandle, mComponent, (int)EZenImuProperty.ZenImuProperty_SamplingRate, 100); // filter mode using accelerometer & gyroscope & magnetometer OpenZen.ZenSensorComponentSetInt32Property(mZenHandle, mSensorHandle, mComponent, (int)EZenImuProperty.ZenImuProperty_FilterMode, 1); // Ensure the Orientation data is streamed out OpenZen.ZenSensorComponentSetBoolProperty(mZenHandle, mSensorHandle, mComponent, (int)EZenImuProperty.ZenImuProperty_OutputQuat, true); print("Sensor 29 configuration complete"); } // print("Trying to connect to OpenZen Sensor on IO " + OpenZenIoType + // " with sensor name " + OpenZenIdentifier2); var sensorInitError2 = OpenZen.ZenObtainSensorByName(mZenHandle, OpenZenIoType, OpenZenIdentifier2, 0, mSensorHandle2); if (sensorInitError2 != ZenSensorInitError.ZenSensorInitError_None) { print("Error while connecting to sensor 98."); } else { ZenComponentHandle_t mComponent2 = new ZenComponentHandle_t(); OpenZen.ZenSensorComponentsByNumber(mZenHandle, mSensorHandle2, OpenZen.g_zenSensorType_Imu, 0, mComponent2); // enable sensor streaming, normally on by default anyways OpenZen.ZenSensorComponentSetBoolProperty(mZenHandle, mSensorHandle2, mComponent2, (int)EZenImuProperty.ZenImuProperty_StreamData, true); // set offset mode to heading OpenZen.ZenSensorComponentSetInt32Property(mZenHandle, mSensorHandle2, mComponent2, (int)EZenImuProperty.ZenImuProperty_OrientationOffsetMode, 1); // set the sampling rate to 100 Hz OpenZen.ZenSensorComponentSetInt32Property(mZenHandle, mSensorHandle2, mComponent2, (int)EZenImuProperty.ZenImuProperty_SamplingRate, 100); // filter mode using accelerometer & gyroscope & magnetometer OpenZen.ZenSensorComponentSetInt32Property(mZenHandle, mSensorHandle2, mComponent2, (int)EZenImuProperty.ZenImuProperty_FilterMode, 1); // Ensure the Orientation data is streamed out OpenZen.ZenSensorComponentSetBoolProperty(mZenHandle, mSensorHandle2, mComponent2, (int)EZenImuProperty.ZenImuProperty_OutputQuat, true); print("Sensor 98 configuration complete"); } var sensorInitError3 = OpenZen.ZenObtainSensorByName(mZenHandle, OpenZenIoType2.ToString(), OpenZenIdentifier3, 0, mSensorHandle3); if (sensorInitError3 != ZenSensorInitError.ZenSensorInitError_None) { print("Error while connecting to sensor USB."); } else { ZenComponentHandle_t mComponent3 = new ZenComponentHandle_t(); OpenZen.ZenSensorComponentsByNumber(mZenHandle, mSensorHandle3, OpenZen.g_zenSensorType_Imu, 0, mComponent3); // enable sensor streaming, normally on by default anyways OpenZen.ZenSensorComponentSetBoolProperty(mZenHandle, mSensorHandle3, mComponent3, (int)EZenImuProperty.ZenImuProperty_StreamData, true); // set offset mode to heading OpenZen.ZenSensorComponentSetInt32Property(mZenHandle, mSensorHandle3, mComponent3, (int)EZenImuProperty.ZenImuProperty_OrientationOffsetMode, 1); // set the sampling rate to 100 Hz OpenZen.ZenSensorComponentSetInt32Property(mZenHandle, mSensorHandle3, mComponent3, (int)EZenImuProperty.ZenImuProperty_SamplingRate, 100); // filter mode using accelerometer & gyroscope & magnetometer OpenZen.ZenSensorComponentSetInt32Property(mZenHandle, mSensorHandle3, mComponent3, (int)EZenImuProperty.ZenImuProperty_FilterMode, 1); // Ensure the Orientation data is streamed out OpenZen.ZenSensorComponentSetBoolProperty(mZenHandle, mSensorHandle3, mComponent3, (int)EZenImuProperty.ZenImuProperty_OutputQuat, true); print("Sensor USB configuration complete"); } // Gripper calibration here: Debug.Log("Begin Gripper Calibration"); }